PR2 / pr2_controllers

The controllers that run in realtime on the PR2 and supporting packages.
46 stars 34 forks source link

JointTrajectoryAction server doesn't abort all goals properly #366

Open calderpg opened 11 years ago

calderpg commented 11 years ago

In the joint_trajectory_action JointTrajectoryExecuter class, in the function controllerStateCB, the following code executes if the end time of the goal has been reached:

      if (inside_goal_constraints)
      {
        active_goal_.setSucceeded();
        has_active_goal_ = false;
      }
      else if (now < end_time + ros::Duration(goal_time_constraint_))
      {
        // Still have some time left to make it.
      }
      else
      {
        ROS_WARN("Aborting because we wound up outside the goal constraints");
        active_goal_.setAborted();
        has_active_goal_ = false;
      }

The final else block appears to abort the goal, however it doesn't also stop the trajectory controller as used elsewhere in the class:

          // Stops the controller.
          trajectory_msgs::JointTrajectory empty;
          empty.joint_names = joint_names_;
          pub_controller_command_.publish(empty);

          active_goal_.setAborted();
          has_active_goal_ = false;
          ROS_WARN("Aborting because we would up outside the trajectory constraints");