25 #ifndef JOINT_TRAJECTORY_ACTION_CONTROLLER_H__ 26 #define JOINT_TRAJECTORY_ACTION_CONTROLLER_H__ 35 #include <trajectory_msgs/JointTrajectory.h> 36 #include <control_msgs/QueryTrajectoryState.h> 37 #include <control_msgs/JointTrajectoryControllerState.h> 39 #include <control_msgs/JointTrajectoryAction.h> 40 #include <control_msgs/FollowJointTrajectoryAction.h> 80 void commandCB(
const trajectory_msgs::JointTrajectory::ConstPtr &msg);
85 control_msgs::QueryTrajectoryState::Response &resp);
94 void executeCB(
const JTAS::GoalConstPtr &goal);
96 int executeCommon(
const trajectory_msgs::JointTrajectory &trajectory, boost::function<
bool ()> isPreemptRequested);
102 bool validJoints(std::vector<std::string> new_joint_names);
104 std::vector<int>
makeJointsLookup(
const trajectory_msgs::JointTrajectory &msg);
void executeCB(const JTAS::GoalConstPtr &goal)
actionlib::SimpleActionClient< control_msgs::JointTrajectoryAction > JTAC
int executeCommon(const trajectory_msgs::JointTrajectory &trajectory, boost::function< bool()> isPreemptRequested)
bool queryStateService(control_msgs::QueryTrajectoryState::Request &req, control_msgs::QueryTrajectoryState::Response &resp)
ros::Subscriber sub_command_
boost::shared_ptr< SpecifiedTrajectory > calculateTrajectory(const trajectory_msgs::JointTrajectory &msg)
ros::Publisher controller_state_publisher_
ros::ServiceServer serve_query_state_
actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > FJTAS
boost::shared_ptr< AbstractKatana > katana_
void commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
void executeCBFollow(const FJTAS::GoalConstPtr &goal)
std::vector< int > makeJointsLookup(const trajectory_msgs::JointTrajectory &msg)
std::vector< Segment > SpecifiedTrajectory
actionlib::SimpleActionServer< control_msgs::JointTrajectoryAction > JTAS
JointTrajectoryActionController(boost::shared_ptr< AbstractKatana > katana)
void reset_trajectory_and_stop()
FJTAS action_server_follow_
std::vector< std::string > joints_
bool validTrajectory(const SpecifiedTrajectory &traj)
double stopped_velocity_tolerance_
boost::shared_ptr< SpecifiedTrajectory > current_trajectory_
bool validJoints(std::vector< std::string > new_joint_names)
std::vector< double > goal_constraints_
virtual ~JointTrajectoryActionController()