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())
98 if (it->second.segment.getJoint().getName() == head_pan_->getName())
118 "Unable to start, not initialized.");
125 "Unable to start, action server is not active.");
142 server_->setAborted(
result_,
"Controller manager forced preemption.");
144 "Controller manager forced preemption.");
197 float head_pan_goal_ = 0.0;
198 float head_tilt_goal_ = 0.0;
201 geometry_msgs::PointStamped target_in_pan, 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)));
210 ROS_WARN_NAMED(
"PointHeadController",
"Could not transform goal.");
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());
261 server_->setAborted(
result_,
"Cannot point head, unable to start controller.");
263 "Cannot point head, unable to start controller.");
270 if (
server_->isPreemptRequested())
272 server_->setPreempted(
result_,
"Pointing of the head has been preempted");
274 "Pointing of the head has been preempted");
292 std::vector<std::string> names;
Basis for a Trajectory Point.
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
#define ROS_WARN_NAMED(name,...)
control_msgs::PointHeadResult result_
Sampler that uses splines.
std::vector< TrajectoryPoint > points
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
const SegmentMap & getSegments() const
virtual int requestStart(const std::string &name)
std::map< std::string, TreeElement > SegmentMap
std::string root_link_
action was preempted (has nothing to do with preempt() above
#define ROS_DEBUG_NAMED(name,...)
virtual int requestStop(const std::string &name)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TrajectoryPoint last_sample_
actionlib::SimpleActionServer< control_msgs::PointHeadAction > head_server_t
JointHandlePtr head_tilt_
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
tf::TransformListener listener_
boost::shared_ptr< TrajectorySampler > sampler_
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
URDF_EXPORT bool initParam(const std::string ¶m)
void executeCb(const control_msgs::PointHeadGoalConstPtr &goal)
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
#define ROS_ERROR_NAMED(name,...)
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
boost::shared_ptr< head_server_t > server_
JointHandlePtr getJointHandle(const std::string &name)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ControllerManager * manager_
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
boost::mutex sampler_mutex_
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.