30 #ifndef GRIPPER_ACTION_CONTROLLER_GRIPPER_ACTION_CONTROLLER_IMPL_H 31 #define GRIPPER_ACTION_CONTROLLER_GRIPPER_ACTION_CONTROLLER_IMPL_H 40 std::size_t
id = complete_ns.find_last_of(
"/");
41 return complete_ns.substr(
id + 1);
50 if (nh.
getParam(param_name, urdf_str))
52 if (!urdf->initString(urdf_str))
54 ROS_ERROR_STREAM(
"Failed to parse URDF contained in '" << param_name <<
"' parameter (namespace: " <<
56 return urdf::ModelSharedPtr();
60 else if (!urdf->initParam(
"robot_description"))
62 ROS_ERROR_STREAM(
"Failed to parse URDF contained in '" << param_name <<
"' parameter");
63 return urdf::ModelSharedPtr();
70 std::vector<urdf::JointConstSharedPtr> out;
71 for (
unsigned int i = 0; i < joint_names.size(); ++i)
73 urdf::JointConstSharedPtr urdf_joint = urdf.getJoint(joint_names[i]);
76 out.push_back(urdf_joint);
80 ROS_ERROR_STREAM(
"Could not find joint '" << joint_names[i] <<
"' in URDF model.");
81 return std::vector<urdf::JointConstSharedPtr>();
89 template <
class HardwareInterface>
93 command_struct_rt_.position_ = joint_.getPosition();
94 command_struct_rt_.max_effort_ = default_max_effort_;
95 command_.initRT(command_struct_rt_);
98 hw_iface_adapter_.starting(
ros::Time(0.0));
99 last_movement_time_ = time;
102 template <
class HardwareInterface>
109 template <
class HardwareInterface>
116 if (current_active_goal)
119 rt_active_goal_.reset();
120 if(current_active_goal->gh_.getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE)
121 current_active_goal->gh_.setCanceled();
125 template <
class HardwareInterface>
131 template <
class HardwareInterface>
136 using namespace internal;
145 double action_monitor_rate = 20.0;
159 urdf::ModelSharedPtr
urdf =
getUrdf(root_nh,
"robot_description");
165 std::vector<std::string> joint_names;
167 std::vector<urdf::JointConstSharedPtr> urdf_joints =
getUrdfJoints(*urdf, joint_names);
168 if (urdf_joints.empty())
192 goal_tolerance_ = fabs(goal_tolerance_);
195 default_max_effort_ = fabs(default_max_effort_);
222 template <
class HardwareInterface>
232 double error_velocity = - current_velocity;
234 checkForSuccess(time, error_position, current_position, current_velocity);
242 template <
class HardwareInterface>
252 control_msgs::GripperCommandResult result;
283 template <
class HardwareInterface>
290 if (current_active_goal && current_active_goal->gh_ == gh)
297 ROS_DEBUG_NAMED(
name_,
"Canceling active action goal because cancel callback recieved from actionlib.");
300 current_active_goal->gh_.setCanceled();
304 template <
class HardwareInterface>
313 template <
class HardwareInterface>
319 if(!current_active_goal)
322 if(current_active_goal->gh_.getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
352 #endif // header guard bool init(hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
ros::Duration action_monitor_period_
void cancelCB(GoalHandle gh)
urdf::ModelSharedPtr getUrdf(const ros::NodeHandle &nh, const std::string ¶m_name)
#define ROS_DEBUG_STREAM_NAMED(name, args)
realtime_tools::RealtimeBuffer< Commands > command_
std::string joint_name_
Controlled joint names.
GripperActionController()
#define ROS_ERROR_STREAM_NAMED(name, args)
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
bool init(HardwareInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
boost::shared_ptr< const Goal > getGoal() const
std::vector< urdf::JointConstSharedPtr > getUrdfJoints(const urdf::Model &urdf, const std::vector< std::string > &joint_names)
double updateCommand(const ros::Time &time, const ros::Duration &period, double desired_position, double desired_velocity, double error_position, double error_velocity, double max_allowed_effort)
std::string getLeafNamespace(const ros::NodeHandle &nh)
std::string getHardwareInterfaceType() const
double computed_command_
Computed command.
ActionServerPtr action_server_
void setAccepted(const std::string &text=std::string(""))
#define ROS_DEBUG_NAMED(name,...)
std::string name_
Controller name.
HwIfaceAdapter hw_iface_adapter_
Adapts desired goal state to HW interface.
ros::Time last_movement_time_
Store stall time.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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.
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
const std::string & getNamespace() const
RealtimeGoalHandlePtr rt_active_goal_
Currently active action goal, if any.
actionlib::ActionServer< control_msgs::GripperCommandAction > ActionServer
double getPosition() const
hardware_interface::JointHandle joint_
Handles to controlled joints.
double getVelocity() const
double stall_velocity_threshold_
Stall related parameters.
void update(const ros::Time &time, const ros::Duration &period)
void setHoldPosition(const ros::Time &time)
void goalCB(GoalHandle gh)
bool getParam(const std::string &key, std::string &s) const
realtime_tools::RealtimeServerGoalHandle< control_msgs::GripperCommandAction > RealtimeGoalHandle
void stopping(const ros::Time &time)
Cancels the active action goal, if any.
#define ROS_ERROR_NAMED(name,...)
double default_max_effort_
Max allowed effort.
ros::NodeHandle controller_nh_
#define ROS_ERROR_STREAM(args)
control_msgs::GripperCommandResultPtr pre_alloc_result_
ros::Timer goal_handle_timer_
Commands command_struct_rt_