58 Controller::init(nh, manager);
62 boost::mutex::scoped_lock lock(sampler_mutex_);
67 nh.
param<
bool>(
"stop_with_action", stop_with_action_,
false);
70 head_pan_ = manager_->getJointHandle(
"head_pan_joint");
71 head_tilt_ = manager_->getJointHandle(
"head_tilt_joint");
75 if (!model.
initParam(
"robot_description"))
78 "Failed to parse URDF, is robot_description parameter set?");
90 for (KDL::SegmentMap::iterator it = segment_map.begin();
91 it != segment_map.end();
94 #ifdef KDL_USE_NEW_TREE_INTERFACE 95 if (it->second->segment.getJoint().getName() == head_pan_->getName())
96 root_link_ = it->second->parent->first;
98 if (it->second.segment.getJoint().getName() == head_pan_->getName())
99 root_link_ = it->second.parent->first;
105 boost::bind(&PointHeadController::executeCb,
this, _1),
113 bool PointHeadController::start()
118 "Unable to start, not initialized.");
122 if (!server_->isActive())
125 "Unable to start, action server is not active.");
132 bool PointHeadController::stop(
bool force)
137 if (server_->isActive())
142 server_->setAborted(result_,
"Controller manager forced preemption.");
144 "Controller manager forced preemption.");
156 bool PointHeadController::reset()
159 return (manager_->requestStop(
getName()) == 0);
168 if (server_->isActive() && sampler_)
170 boost::mutex::scoped_lock lock(sampler_mutex_);
177 if (now.
toSec() > sampler_->end_time())
178 server_->setSucceeded(result_,
"OK");
183 head_pan_->setPosition(p.
q[0], p.
qd[0], 0.0);
184 head_tilt_->setPosition(p.
q[1], p.
qd[1], 0.0);
187 else if (last_sample_.q.size() == 2)
190 head_pan_->setPosition(last_sample_.q[0], 0.0, 0.0);
191 head_tilt_->setPosition(last_sample_.q[1], 0.0, 0.0);
195 void PointHeadController::executeCb(
const control_msgs::PointHeadGoalConstPtr& goal)
197 float head_pan_goal_ = 0.0;
198 float head_tilt_goal_ = 0.0;
201 geometry_msgs::PointStamped target_in_pan, target_in_tilt;
202 listener_.transformPoint(root_link_,
ros::Time(0), goal->target, goal->target.header.frame_id, target_in_pan);
203 listener_.transformPoint(
"head_pan_link",
ros::Time(0), goal->target, goal->target.header.frame_id, target_in_tilt);
204 head_pan_goal_ =
atan2(target_in_pan.point.y, target_in_pan.point.x);
205 head_tilt_goal_ = -
atan2(target_in_tilt.point.z,
sqrt(
pow(target_in_tilt.point.x, 2) +
pow(target_in_tilt.point.y, 2)));
209 server_->setAborted(result_,
"Could not transform goal.");
210 ROS_WARN_NAMED(
"PointHeadController",
"Could not transform goal.");
220 t.
points[0] = last_sample_;
225 t.
points[0].q.push_back(head_pan_->getPosition());
226 t.
points[0].q.push_back(head_tilt_->getPosition());
227 t.
points[0].qd.push_back(0.0);
228 t.
points[0].qd.push_back(0.0);
229 t.
points[0].qdd.push_back(0.0);
230 t.
points[0].qdd.push_back(0.0);
235 t.
points[1].q.push_back(head_pan_goal_);
236 t.
points[1].q.push_back(head_tilt_goal_);
237 t.
points[1].qd.push_back(0.0);
238 t.
points[1].qd.push_back(0.0);
239 t.
points[1].qdd.push_back(0.0);
240 t.
points[1].qdd.push_back(0.0);
243 double max_pan_vel = head_pan_->getVelocityMax();
244 double max_tilt_vel = head_tilt_->getVelocityMax();
245 if (goal->max_velocity > 0.0)
247 max_pan_vel = fmin(goal->max_velocity, head_pan_->getVelocityMax());
248 max_tilt_vel = fmin(goal->max_velocity, head_tilt_->getVelocityMax());
250 double pan_transit = fabs((t.
points[1].q[0] - t.
points[0].q[0]) / max_pan_vel);
251 double tilt_transit = fabs((t.
points[1].q[1] - t.
points[0].q[1]) / max_tilt_vel);
252 t.
points[1].time = t.
points[0].time + fmax(fmax(pan_transit, tilt_transit), goal->min_duration.toSec());
255 boost::mutex::scoped_lock lock(sampler_mutex_);
259 if (manager_->requestStart(
getName()) != 0)
261 server_->setAborted(result_,
"Cannot point head, unable to start controller.");
263 "Cannot point head, unable to start controller.");
268 while (server_->isActive())
270 if (server_->isPreemptRequested())
272 server_->setPreempted(result_,
"Pointing of the head has been preempted");
274 "Pointing of the head has been preempted");
284 if (stop_with_action_ && !preempted_)
285 manager_->requestStop(
getName());
290 std::vector<std::string> PointHeadController::getCommandedNames()
292 std::vector<std::string> names;
293 names.push_back(head_pan_->getName());
294 names.push_back(head_tilt_->getName());
298 std::vector<std::string> PointHeadController::getClaimedNames()
301 return getCommandedNames();
Basis for a Trajectory Point.
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
#define ROS_WARN_NAMED(name,...)
Sampler that uses splines.
std::vector< TrajectoryPoint > points
std::string getName(void *handle)
std::map< std::string, TreeElement > SegmentMap
#define ROS_DEBUG_NAMED(name,...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
URDF_EXPORT bool initParam(const std::string ¶m)
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
#define ROS_ERROR_NAMED(name,...)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)