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

[velocity_controllers] Add timeout to JointGroupVelocityController #582

Open
wants to merge 2 commits into
base: noetic-devel
Choose a base branch
from
Open
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 @@ -103,6 +103,13 @@ class ForwardJointGroupCommandController: public controller_interface::Controlle
}
}

// Check if timeout parameter has been set. Read it if set, otherwise warn about unsafe default behaviour.
if(n.hasParam("command_timeout"))
{
n.getParam("command_timeout", command_timeout_);
ROS_INFO_STREAM("Using command timeout: " << command_timeout_);
}

commands_buffer_.writeFromNonRT(std::vector<double>(n_joints_, 0.0));

sub_command_ = n.subscribe<std_msgs::Float64MultiArray>("command", 1, &ForwardJointGroupCommandController::commandCB, this);
Expand All @@ -120,6 +127,8 @@ class ForwardJointGroupCommandController: public controller_interface::Controlle
std::vector< std::string > joint_names_;
std::vector< hardware_interface::JointHandle > joints_;
realtime_tools::RealtimeBuffer<std::vector<double> > commands_buffer_;
realtime_tools::RealtimeBuffer<ros::Time> last_received_command_time_buffer_;
double command_timeout_ = -1.0;
unsigned int n_joints_;

private:
Expand All @@ -132,6 +141,9 @@ class ForwardJointGroupCommandController: public controller_interface::Controlle
return;
}
commands_buffer_.writeFromNonRT(msg->data);

// Record time of last received command
last_received_command_time_buffer_.writeFromNonRT(ros::Time::now());
}
};

Expand Down
25 changes: 23 additions & 2 deletions velocity_controllers/src/joint_group_velocity_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,33 @@
#include <velocity_controllers/joint_group_velocity_controller.h>
#include <pluginlib/class_list_macros.hpp>

template <class T>
void forward_command_controller::ForwardJointGroupCommandController<T>::starting(const ros::Time& time)
template<>
void velocity_controllers::JointGroupVelocityController::starting(const ros::Time& /*time*/)
{
// Start controller with 0.0 velocities
commands_buffer_.readFromRT()->assign(n_joints_, 0.0);
}

template<>
void velocity_controllers::JointGroupVelocityController::update(const ros::Time& time, const ros::Duration& /*period*/)
{
std::vector<double> & commands = *commands_buffer_.readFromRT();

// Check timeout
if (command_timeout_ > 0.0)
{
ros::Time& last_received_command_time = *last_received_command_time_buffer_.readFromRT();
const double command_age = (time - last_received_command_time).toSec();
if (std::abs(command_age) > command_timeout_)
{
ROS_WARN_STREAM_THROTTLE(10, "Commands timed out, setting to zero.");
for (std::size_t i = 0; i < commands.size(); ++i)
{ commands[i] = 0; }
}
}

for(unsigned int i=0; i<n_joints_; i++)
{ joints_[i].setCommand(commands[i]); }
}

PLUGINLIB_EXPORT_CLASS(velocity_controllers::JointGroupVelocityController,controller_interface::ControllerBase)