40 #include <trajectory_msgs/JointTrajectory.h> 41 #include <pr2_controllers_msgs/SingleJointPositionAction.h> 42 #include <pr2_controllers_msgs/QueryTrajectoryState.h> 43 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h> 79 ROS_WARN(
"The controller does not appear to be ready (the query_state service is not available)");
93 pr2_controllers_msgs::QueryTrajectoryState traj_state;
97 ROS_ERROR(
"Service call to query controller trajectory failed. Service: (%s)",
117 if (gh.
getGoal()->min_duration > min_duration)
118 min_duration = gh.
getGoal()->min_duration;
122 if (gh.
getGoal()->max_velocity > 0)
125 double dist = fabs(gh.
getGoal()->position - traj_state.response.position[0]);
128 if (limit_from_velocity > min_duration)
129 min_duration = limit_from_velocity;
133 trajectory_msgs::JointTrajectory traj;
134 traj.header.stamp = traj_state.request.time;
136 traj.joint_names.push_back(
joint_);
138 traj.points.resize(2);
139 traj.points[0].positions = traj_state.response.position;
140 traj.points[0].velocities = traj_state.response.velocity;
142 traj.points[1].positions.push_back(gh.
getGoal()->position);
143 traj.points[1].velocities.push_back(0);
144 traj.points[1].time_from_start =
ros::Duration(min_duration);
171 if (has_active_goal_)
173 bool should_abort =
false;
177 ROS_WARN(
"Aborting goal because we have never heard a controller state message.");
182 ROS_WARN(
"Aborting goal because we haven't heard from the controller in %.3lf seconds",
189 trajectory_msgs::JointTrajectory empty;
190 empty.joint_names.push_back(joint_);
191 pub_controller_command_.
publish(empty);
195 has_active_goal_ =
false;
202 if (active_goal_ == gh)
205 trajectory_msgs::JointTrajectory empty;
206 empty.joint_names.push_back(joint_);
207 pub_controller_command_.
publish(empty);
211 has_active_goal_ =
false;
218 last_controller_state_ = msg;
221 if (!has_active_goal_)
224 pr2_controllers_msgs::SingleJointPositionFeedback feedback;
225 feedback.header.stamp = msg->header.stamp;
226 feedback.position = msg->actual.positions[0];
227 feedback.velocity = msg->actual.velocities[0];
228 feedback.error = msg->error.positions[0];
231 if (fabs(msg->actual.positions[0] - active_goal_.
getGoal()->position) < goal_threshold_)
234 has_active_goal_ =
false;
240 int main(
int argc,
char** argv)
242 ros::init(argc, argv,
"position_joint_action_node");
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publishFeedback(const Feedback &feedback)
int main(int argc, char **argv)
void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_controller_state_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void goalCB(GoalHandle gh)
bool call(MReq &req, MRes &res)
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
boost::shared_ptr< const Goal > getGoal() const
void cancelCB(GoalHandle gh)
actionlib::ActionServer< pr2_controllers_msgs::SingleJointPositionAction > SJPAS
pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
ros::ServiceClient cli_query_traj_
void setAccepted(const std::string &text=std::string(""))
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
SJPAS::GoalHandle GoalHandle
bool getParam(const std::string &key, std::string &s) const
ros::Timer watchdog_timer_
SingleJointPositionNode(const ros::NodeHandle &n)
void watchdog(const ros::TimerEvent &e)
ros::Subscriber command_sub_
ros::Publisher pub_controller_command_