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

JointGroupVelocityController: stop motion if no commands received #625

Open
wants to merge 1 commit 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 @@ -57,7 +57,17 @@ namespace velocity_controllers
* Subscribes to:
* - \b command (std_msgs::Float64MultiArray) : The joint velocities to apply
*/
typedef forward_command_controller::ForwardJointGroupCommandController<hardware_interface::VelocityJointInterface>
JointGroupVelocityController;
class JointGroupVelocityController : public forward_command_controller::ForwardJointGroupCommandController<hardware_interface::VelocityJointInterface>
{
using BaseClass = forward_command_controller::ForwardJointGroupCommandController<hardware_interface::VelocityJointInterface>;
bool received_;
ros::WallTimer watchdog_;
ros::Subscriber sub_command_;
void commandCB(const std_msgs::Float64MultiArrayConstPtr&);
void watchDogCB(const ros::WallTimerEvent& event);

public:
bool init(hardware_interface::VelocityJointInterface* hw, ros::NodeHandle &nh) override;
};

}
30 changes: 30 additions & 0 deletions velocity_controllers/src/joint_group_velocity_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,5 +45,35 @@ void forward_command_controller::ForwardJointGroupCommandController<T>::starting
commands_buffer_.readFromRT()->assign(n_joints_, 0.0);
}

namespace velocity_controllers
{
bool JointGroupVelocityController::init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &nh) {
if (!BaseClass::init(hw, nh))
return false;

double timeout;
if (!nh.param("watchdog_timeout", timeout, 1.0))
ROS_WARN_STREAM("No watchdog_timeout parameter, defaulting to " << timeout);
watchdog_ = nh.createWallTimer(ros::WallDuration(timeout), &JointGroupVelocityController::watchDogCB, this, false, false);
sub_command_ = nh.subscribe<std_msgs::Float64MultiArray>("command", 1, &JointGroupVelocityController::commandCB, this);
return true;
}
void JointGroupVelocityController::commandCB(const std_msgs::Float64MultiArrayConstPtr&) {
received_ = true;
watchdog_.start(); // (re)start watchdog timer
}
void JointGroupVelocityController::watchDogCB(const ros::WallTimerEvent&) {
if (!isRunning()) {
watchdog_.stop();
}
else if (!received_) {
ROS_WARN("Didn't receive new velocity commands: stopping motion");
std::vector<double> zeros(n_joints_, 0.0);
commands_buffer_.writeFromNonRT(zeros);
watchdog_.stop(); // wait for message before starting again
}
received_ = false;
}
}

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