Go to the documentation of this file.
40 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactAction.h>
41 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactData.h>
42 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactCommand.h>
43 #include <std_srvs/Empty.h>
62 node_.
advertise<pr2_gripper_sensor_msgs::PR2GripperFindContactCommand>(
"find_contact", 1);
101 bool should_abort =
false;
105 ROS_WARN(
"Aborting goal because we have never heard a controller state message.");
110 ROS_WARN(
"Aborting goal because we haven't heard from the controller in %.3lf seconds",
139 if(
active_goal_.getGoal()->command.zero_fingertip_sensors)
141 std_srvs::Empty::Request req;
142 std_srvs::Empty::Response
resp;
163 std_srvs::Empty::Request req;
164 std_srvs::Empty::Response
resp;
187 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal goal;
190 pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback feedback;
191 feedback.data = *
msg;
193 pr2_gripper_sensor_msgs::PR2GripperFindContactResult result;
202 else if(feedback.data.rtstate.realtime_controller_state == 5 || feedback.data.rtstate.realtime_controller_state == 3)
204 if(feedback.data.contact_conditions_met)
219 int main(
int argc,
char** argv)
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
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())
ServerGoalHandle< ActionSpec > GoalHandle
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const