37 #include <boost/bind.hpp>
42 #include <trajectory_msgs/JointTrajectory.h>
43 #include <pr2_controllers_msgs/SingleJointPositionAction.h>
44 #include <pr2_controllers_msgs/QueryTrajectoryState.h>
45 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
81 ROS_WARN(
"The controller does not appear to be ready (the query_state service is not available)");
95 pr2_controllers_msgs::QueryTrajectoryState traj_state;
99 ROS_ERROR(
"Service call to query controller trajectory failed. Service: (%s)",
119 if (gh.getGoal()->min_duration > min_duration)
120 min_duration = gh.getGoal()->min_duration;
124 if (gh.getGoal()->max_velocity > 0)
127 double dist = fabs(gh.getGoal()->position - traj_state.response.position[0]);
128 ros::Duration limit_from_velocity(dist / gh.getGoal()->max_velocity);
130 if (limit_from_velocity > min_duration)
131 min_duration = limit_from_velocity;
135 trajectory_msgs::JointTrajectory traj;
136 traj.header.stamp = traj_state.request.time;
138 traj.joint_names.push_back(
joint_);
140 traj.points.resize(2);
141 traj.points[0].positions = traj_state.response.position;
142 traj.points[0].velocities = traj_state.response.velocity;
144 traj.points[1].positions.push_back(gh.getGoal()->position);
145 traj.points[1].velocities.push_back(0);
146 traj.points[1].time_from_start =
ros::Duration(min_duration);
175 bool should_abort =
false;
179 ROS_WARN(
"Aborting goal because we have never heard a controller state message.");
184 ROS_WARN(
"Aborting goal because we haven't heard from the controller in %.3lf seconds",
191 trajectory_msgs::JointTrajectory empty;
207 trajectory_msgs::JointTrajectory empty;
208 empty.joint_names.push_back(
joint_);
218 void controllerStateCB(
const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
226 pr2_controllers_msgs::SingleJointPositionFeedback feedback;
227 feedback.header.stamp = msg->header.stamp;
228 feedback.position = msg->actual.positions[0];
229 feedback.velocity = msg->actual.velocities[0];
230 feedback.error = msg->error.positions[0];
242 int main(
int argc,
char** argv)
244 ros::init(argc, argv,
"position_joint_action_node");