Go to the documentation of this file.
34 #include <boost/bind.hpp>
37 #include <pr2_controllers_msgs/JointControllerState.h>
38 #include <pr2_controllers_msgs/Pr2GripperCommand.h>
39 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
62 node_.
advertise<pr2_controllers_msgs::Pr2GripperCommand>(
"command", 1);
102 bool should_abort =
false;
106 ROS_WARN(
"Aborting goal because we have never heard a controller state message.");
111 ROS_WARN(
"Aborting goal because we haven't heard from the controller in %.3lf seconds",
152 pr2_controllers_msgs::Pr2GripperCommand stop;
154 stop.max_effort = 0.0;
184 ROS_ERROR(
"Cancelling goal: Controller is trying to achieve a different setpoint.");
191 pr2_controllers_msgs::Pr2GripperCommandFeedback feedback;
192 feedback.position =
msg->process_value;
193 feedback.effort =
msg->command;
194 feedback.reached_goal =
false;
195 feedback.stalled =
false;
197 pr2_controllers_msgs::Pr2GripperCommandResult result;
198 result.position =
msg->process_value;
199 result.effort =
msg->command;
200 result.reached_goal =
false;
201 result.stalled =
false;
205 feedback.reached_goal =
true;
207 result.reached_goal =
true;
221 feedback.stalled =
true;
223 result.stalled =
true;
233 int main(
int argc,
char** argv)
boost::shared_ptr< const Goal > getGoal() const
void publishFeedback(const Feedback &feedback)
ros::Publisher pub_controller_command_
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::Time last_movement_time_
pr2_controllers_msgs::JointControllerStateConstPtr last_controller_state_
void controllerStateCB(const pr2_controllers_msgs::JointControllerStateConstPtr &msg)
void goalCB(GoalHandle gh)
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
double stall_velocity_threshold_
int main(int argc, char **argv)
void cancelCB(GoalHandle gh)
void setAccepted(const std::string &text=std::string(""))
ros::Timer watchdog_timer_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
GAS::GoalHandle GoalHandle
actionlib::ActionServer< pr2_controllers_msgs::Pr2GripperCommandAction > GAS
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void watchdog(const ros::TimerEvent &e)
T param(const std::string ¶m_name, const T &default_val) const
Pr2GripperAction(ros::NodeHandle &n)
ros::Subscriber sub_controller_state_
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const