35 #include <pr2_controllers_msgs/JointControllerState.h> 36 #include <pr2_controllers_msgs/Pr2GripperCommand.h> 37 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h> 60 node_.
advertise<pr2_controllers_msgs::Pr2GripperCommand>(
"command", 1);
100 bool should_abort =
false;
104 ROS_WARN(
"Aborting goal because we have never heard a controller state message.");
109 ROS_WARN(
"Aborting goal because we haven't heard from the controller in %.3lf seconds",
117 has_active_goal_ =
false;
125 if (has_active_goal_)
129 has_active_goal_ =
false;
134 has_active_goal_ =
true;
136 min_error_seen_ = 1e10;
145 if (active_goal_ == gh)
150 pr2_controllers_msgs::Pr2GripperCommand stop;
152 stop.max_effort = 0.0;
153 pub_controller_command_.
publish(stop);
158 has_active_goal_ =
false;
167 last_controller_state_ = msg;
170 if (!has_active_goal_)
174 if (fabs(msg->set_point - active_goal_.
getGoal()->command.position) > goal_threshold_)
182 ROS_ERROR(
"Cancelling goal: Controller is trying to achieve a different setpoint.");
184 has_active_goal_ =
false;
189 pr2_controllers_msgs::Pr2GripperCommandFeedback feedback;
190 feedback.position = msg->process_value;
191 feedback.effort = msg->command;
192 feedback.reached_goal =
false;
193 feedback.stalled =
false;
195 pr2_controllers_msgs::Pr2GripperCommandResult result;
196 result.position = msg->process_value;
197 result.effort = msg->command;
198 result.reached_goal =
false;
199 result.stalled =
false;
201 if (fabs(msg->process_value - active_goal_.
getGoal()->command.position) < goal_threshold_)
203 feedback.reached_goal =
true;
205 result.reached_goal =
true;
207 has_active_goal_ =
false;
212 if (fabs(msg->process_value_dot) > stall_velocity_threshold_)
216 else if ((
ros::Time::now() - last_movement_time_).toSec() > stall_timeout_ &&
217 active_goal_.
getGoal()->command.max_effort != 0.0)
219 feedback.stalled =
true;
221 result.stalled =
true;
223 has_active_goal_ =
false;
231 int main(
int argc,
char** argv)
233 ros::init(argc, argv,
"gripper_action_node");
void publishFeedback(const Feedback &feedback)
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())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void cancelCB(GoalHandle gh)
boost::shared_ptr< const Goal > getGoal() const
Pr2GripperAction(ros::NodeHandle &n)
ros::Time last_movement_time_
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
ROSCPP_DECL void spin(Spinner &spinner)
void setAccepted(const std::string &text=std::string(""))
void goalCB(GoalHandle gh)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ros::Subscriber sub_controller_state_
GAS::GoalHandle GoalHandle
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
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
actionlib::ActionServer< pr2_controllers_msgs::Pr2GripperCommandAction > GAS
void controllerStateCB(const pr2_controllers_msgs::JointControllerStateConstPtr &msg)
pr2_controllers_msgs::JointControllerStateConstPtr last_controller_state_
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
double stall_velocity_threshold_
void watchdog(const ros::TimerEvent &e)
ros::Timer watchdog_timer_
ros::Publisher pub_controller_command_