Skip to content

Commit

Permalink
traj_action: split cancelling goal and stopping relay
Browse files Browse the repository at this point in the history
So we can reuse stopping the relay.
  • Loading branch information
gavanderhoorn committed Jun 28, 2021
1 parent e1d78ce commit 22e3a09
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -245,6 +245,11 @@ class JointTrajectoryAction
*/
void robotStatusCB(const industrial_msgs::RobotStatusConstPtr &msg);

/**
* \brief Sends a stop command (empty message) to the robot driver.
*/
void stopRelay();

/**
* \brief Aborts the current action goal and sends a stop command
* (empty message) to the robot driver.
Expand Down
14 changes: 7 additions & 7 deletions industrial_robot_client/src/joint_trajectory_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,9 +272,7 @@ void JointTrajectoryAction::cancelCB(JointTractoryActionServer::GoalHandle gh)
if (active_goal_ == gh)
{
// Stops the controller.
trajectory_msgs::JointTrajectory empty;
empty.joint_names = joint_names_;
pub_trajectory_command_.publish(empty);
stopRelay();

// Marks the current goal as canceled.
active_goal_.setCanceled();
Expand Down Expand Up @@ -323,9 +321,7 @@ void JointTrajectoryAction::controllerStateCB(const control_msgs::FollowJointTra
+ describe_robot_status_msg(last_robot_status_, consider_status_unknowns_ok_) };

// Stop the relay
trajectory_msgs::JointTrajectory empty;
empty.joint_names = joint_names_;
pub_trajectory_command_.publish(empty);
stopRelay();

// return abort to action client
control_msgs::FollowJointTrajectoryResult result;
Expand Down Expand Up @@ -384,12 +380,16 @@ void JointTrajectoryAction::controllerStateCB(const control_msgs::FollowJointTra
}
}

void JointTrajectoryAction::abortGoal()
void JointTrajectoryAction::stopRelay()
{
// Stops the controller.
trajectory_msgs::JointTrajectory empty;
pub_trajectory_command_.publish(empty);
}

void JointTrajectoryAction::abortGoal()
{
stopRelay();
// Marks the current goal as aborted.
active_goal_.setAborted();
has_active_goal_ = false;
Expand Down

0 comments on commit 22e3a09

Please sign in to comment.