Go to the documentation of this file.
40 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoAction.h>
41 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoData.h>
42 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoCommand.h>
43 #include <std_srvs/Empty.h>
67 node_.
advertise<pr2_gripper_sensor_msgs::PR2GripperSlipServoCommand>(
"slip_servo", 1);
109 bool should_abort =
false;
113 ROS_WARN(
"Aborting goal because we have never heard a controller state message.");
118 ROS_WARN(
"Aborting goal because we haven't heard from the controller in %.3lf seconds",
160 std_srvs::Empty::Request req;
161 std_srvs::Empty::Response
resp;
184 pr2_gripper_sensor_msgs::PR2GripperSlipServoGoal goal;
187 pr2_gripper_sensor_msgs::PR2GripperSlipServoFeedback feedback;
188 feedback.data = *
msg;
190 pr2_gripper_sensor_msgs::PR2GripperSlipServoResult result;
198 else if(feedback.data.rtstate.realtime_controller_state == 6)
209 int main(
int argc,
char** argv)
actionlib::ActionServer< pr2_gripper_sensor_msgs::PR2GripperSlipServoAction > GAS
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
bool call(const std::string &service_name, MReq &req, MRes &res)
boost::shared_ptr< const Goal > getGoal() const
void publishFeedback(const Feedback &feedback)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
pr2_gripper_sensor_msgs::PR2GripperSlipServoDataConstPtr last_controller_state_
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)
void goalCB(GoalHandle gh)
ros::Time action_start_time
void setAccepted(const std::string &text=std::string(""))
Pr2GripperSlipServo(ros::NodeHandle &n)
ros::Timer watchdog_timer_
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
void controllerStateCB(const pr2_gripper_sensor_msgs::PR2GripperSlipServoDataConstPtr &msg)
ros::Publisher pub_controller_command_
int main(int argc, char **argv)
void watchdog(const ros::TimerEvent &e)
ros::Time last_movement_time_
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
double stall_velocity_threshold_
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
void cancelCB(GoalHandle gh)
ros::Subscriber sub_controller_state_