42 std::size_t
id = complete_ns.find_last_of(
"/");
43 return complete_ns.substr(
id + 1);
52 if (nh.
getParam(param_name, urdf_str))
54 if (!
urdf->initString(urdf_str))
56 ROS_ERROR_STREAM(
"Failed to parse URDF contained in '" << param_name <<
"' parameter (namespace: " <<
58 return urdf::ModelSharedPtr();
62 else if (!
urdf->initParam(
"robot_description"))
64 ROS_ERROR_STREAM(
"Failed to parse URDF contained in '" << param_name <<
"' parameter");
65 return urdf::ModelSharedPtr();
72 std::vector<urdf::JointConstSharedPtr> out;
73 for (
const auto& joint_name : joint_names)
75 urdf::JointConstSharedPtr urdf_joint =
urdf.getJoint(joint_name);
78 out.push_back(urdf_joint);
82 ROS_ERROR_STREAM(
"Could not find joint '" << joint_name <<
"' in URDF model.");
83 return std::vector<urdf::JointConstSharedPtr>();
91 template <
class HardwareInterface>
95 command_struct_rt_.position_ = joint_.getPosition();
96 command_struct_rt_.max_effort_ = default_max_effort_;
97 command_.initRT(command_struct_rt_);
100 hw_iface_adapter_.starting(
ros::Time(0.0));
101 last_movement_time_ = time;
104 template <
class HardwareInterface>
111 template <
class HardwareInterface>
118 if (current_active_goal)
121 rt_active_goal_.reset();
122 if(current_active_goal->gh_.getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE)
123 current_active_goal->gh_.setCanceled();
127 template <
class HardwareInterface>
133 template <
class HardwareInterface>
138 using namespace internal;
141 controller_nh_ = controller_nh;
147 double action_monitor_rate = 20.0;
148 controller_nh_.getParam(
"action_monitor_rate", action_monitor_rate);
149 action_monitor_period_ =
ros::Duration(1.0 / action_monitor_rate);
150 ROS_DEBUG_STREAM_NAMED(name_,
"Action status changes will be monitored at " << action_monitor_rate <<
"Hz.");
153 controller_nh_.getParam(
"joint", joint_name_);
154 if (joint_name_.empty())
161 urdf::ModelSharedPtr
urdf =
getUrdf(root_nh,
"robot_description");
167 std::vector<std::string> joint_names;
168 joint_names.push_back(joint_name_);
169 std::vector<urdf::JointConstSharedPtr> urdf_joints =
getUrdfJoints(*
urdf, joint_names);
170 if (urdf_joints.empty())
179 joint_ = hw->getHandle(joint_name_);
184 this->getHardwareInterfaceType() <<
"'.");
189 "\n- Hardware interface type: '" << this->getHardwareInterfaceType() <<
"'" <<
193 controller_nh_.param<
double>(
"goal_tolerance", goal_tolerance_, 0.01);
194 goal_tolerance_ = fabs(goal_tolerance_);
196 controller_nh_.param<
double>(
"max_effort", default_max_effort_, 0.0);
197 default_max_effort_ = fabs(default_max_effort_);
199 controller_nh_.param<
double>(
"stall_velocity_threshold", stall_velocity_threshold_, 0.001);
200 controller_nh_.param<
double>(
"stall_timeout", stall_timeout_, 1.0);
203 hw_iface_adapter_.init(joint_, controller_nh_);
206 command_struct_.position_ = joint_.getPosition();
207 command_struct_.max_effort_ = default_max_effort_;
210 pre_alloc_result_.reset(
new control_msgs::GripperCommandResult());
211 pre_alloc_result_->position = command_struct_.position_;
212 pre_alloc_result_->reached_goal =
false;
213 pre_alloc_result_->stalled =
false;
219 action_server_->start();
223 template <
class HardwareInterface>
227 command_struct_rt_ = *(command_.readFromRT());
229 double current_position = joint_.getPosition();
230 double current_velocity = joint_.getVelocity();
232 double error_position = command_struct_rt_.position_ - current_position;
233 double error_velocity = - current_velocity;
235 checkForSuccess(time, error_position, current_position, current_velocity);
238 computed_command_ = hw_iface_adapter_.updateCommand(time, period,
239 command_struct_rt_.position_, 0.0,
240 error_position, error_velocity, command_struct_rt_.max_effort_);
243 template <
class HardwareInterface>
250 if (!this->isRunning())
252 ROS_ERROR_NAMED(name_,
"Can't accept new action goals. Controller is not running.");
253 control_msgs::GripperCommandResult result;
267 command_struct_.position_ = gh.
getGoal()->command.position;
268 command_struct_.max_effort_ = gh.
getGoal()->command.max_effort;
269 command_.writeFromNonRT(command_struct_);
271 pre_alloc_result_->reached_goal =
false;
272 pre_alloc_result_->stalled =
false;
277 goal_handle_timer_ = controller_nh_.createTimer(action_monitor_period_,
278 &RealtimeGoalHandle::runNonRealtime,
280 goal_handle_timer_.start();
281 rt_active_goal_ = rt_goal;
284 template <
class HardwareInterface>
291 if (current_active_goal && current_active_goal->gh_ == gh)
294 rt_active_goal_.reset();
298 ROS_DEBUG_NAMED(name_,
"Canceling active action goal because cancel callback recieved from actionlib.");
301 current_active_goal->gh_.setCanceled();
305 template <
class HardwareInterface>
309 command_struct_.position_ = joint_.getPosition();
310 command_struct_.max_effort_ = default_max_effort_;
311 command_.writeFromNonRT(command_struct_);
314 template <
class HardwareInterface>
320 if(!current_active_goal)
323 if(current_active_goal->gh_.getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
326 if(fabs(error_position) < goal_tolerance_)
328 pre_alloc_result_->effort = computed_command_;
329 pre_alloc_result_->position = current_position;
330 pre_alloc_result_->reached_goal =
true;
331 pre_alloc_result_->stalled =
false;
332 current_active_goal->setSucceeded(pre_alloc_result_);
336 if(fabs(current_velocity) > stall_velocity_threshold_)
338 last_movement_time_ = time;
340 else if( (time - last_movement_time_).toSec() > stall_timeout_)
342 pre_alloc_result_->effort = computed_command_;
343 pre_alloc_result_->position = current_position;
344 pre_alloc_result_->reached_goal =
false;
345 pre_alloc_result_->stalled =
true;
346 current_active_goal->setAborted(pre_alloc_result_);