30 #ifndef GRIPPER_ACTION_CONTROLLER_GRIPPER_ACTION_CONTROLLER_H 31 #define GRIPPER_ACTION_CONTROLLER_GRIPPER_ACTION_CONTROLLER_H 40 #include <boost/shared_ptr.hpp> 41 #include <boost/scoped_ptr.hpp> 50 #include <control_msgs/GripperCommandAction.h> 74 template <
class HardwareInterface>
139 void goalCB(GoalHandle gh);
153 void checkForSuccess(
const ros::Time& time,
double error_position,
double current_position,
double current_velocity);
161 #endif // header guard
ros::Duration action_monitor_period_
void cancelCB(GoalHandle gh)
realtime_tools::RealtimeBuffer< Commands > command_
std::string joint_name_
Controlled joint names.
GripperActionController()
boost::shared_ptr< ActionServer > ActionServerPtr
bool init(HardwareInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
boost::shared_ptr< RealtimeGoalHandle > RealtimeGoalHandlePtr
double computed_command_
Computed command.
ActionServerPtr action_server_
std::string name_
Controller name.
HwIfaceAdapter hw_iface_adapter_
Adapts desired goal state to HW interface.
bool verbose_
Hard coded verbose flag to help in debugging.
bool update_hold_position_
ros::Time last_movement_time_
Store stall time.
void checkForSuccess(const ros::Time &time, double error_position, double current_position, double current_velocity)
Check for success and publish appropriate result and feedback.
void starting(const ros::Time &time)
Holds the current position.
RealtimeGoalHandlePtr rt_active_goal_
Currently active action goal, if any.
actionlib::ActionServer< control_msgs::GripperCommandAction > ActionServer
hardware_interface::JointHandle joint_
Handles to controlled joints.
double stall_velocity_threshold_
Stall related parameters.
void update(const ros::Time &time, const ros::Duration &period)
void setHoldPosition(const ros::Time &time)
Helper class to simplify integrating the GripperActionController with different hardware interfaces...
void goalCB(GoalHandle gh)
realtime_tools::RealtimeServerGoalHandle< control_msgs::GripperCommandAction > RealtimeGoalHandle
void stopping(const ros::Time &time)
Cancels the active action goal, if any.
Store position and max effort in struct to allow easier realtime buffer usage.
double default_max_effort_
Max allowed effort.
ros::NodeHandle controller_nh_
HardwareInterfaceAdapter< HardwareInterface > HwIfaceAdapter
Controller for executing a gripper command action for simple single-dof grippers. ...
control_msgs::GripperCommandResultPtr pre_alloc_result_
ros::Timer goal_handle_timer_
ActionServer::GoalHandle GoalHandle
Commands command_struct_rt_