Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix joint state controller exception starting with 0 time #629

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,6 @@ class JointStateController: public controller_interface::Controller<hardware_int
ros::Time last_publish_time_;
double publish_rate_;
unsigned int num_hw_joints_; ///< Number of joints present in the JointStateInterface, excluding extra joints
bool pub_time_initialized_;

void addExtraJoints(const ros::NodeHandle& nh, sensor_msgs::JointState& msg);
};
Expand Down
11 changes: 1 addition & 10 deletions joint_state_controller/src/joint_state_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,26 +80,17 @@ namespace joint_state_controller
}
addExtraJoints(controller_nh, realtime_pub_->msg_);

pub_time_initialized_=false;

return true;
}

void JointStateController::starting(const ros::Time& time)
{
// initialize time exactly once, to maintain publish rate through controller resets
if (!pub_time_initialized_)
{
last_publish_time_ = time - ros::Duration(1.001/publish_rate_); //ensure publish on first cycle
pub_time_initialized_ = true;
}
}

void JointStateController::update(const ros::Time& time, const ros::Duration& /*period*/)
{
// limit rate of publishing
if (publish_rate_ > 0.0 && last_publish_time_ + ros::Duration(1.0/publish_rate_) < time){

if (publish_rate_ > 0.0 && (last_publish_time_.isZero() || last_publish_time_ + ros::Duration(1.0/publish_rate_) < time)){
// try to publish
if (realtime_pub_->trylock()){
// we're actually publishing, so increment time
Expand Down