38 #include <boost/bind.hpp>
39 #include <boost/scoped_ptr.hpp>
42 #include <geometry_msgs/PoseStamped.h>
43 #include <geometry_msgs/PointStamped.h>
44 #include <geometry_msgs/Twist.h>
46 #include <kdl/chainfksolver.hpp>
47 #include <kdl/chain.hpp>
48 #include <kdl/chainjnttojacsolver.hpp>
49 #include <kdl/frames.hpp>
50 #include "kdl/chainfksolverpos_recursive.hpp"
59 #include <sensor_msgs/JointState.h>
60 #include <std_msgs/Float32MultiArray.h>
61 #include <std_msgs/Int32.h>
65 #include <trajectory_msgs/JointTrajectory.h>
66 #include <pr2_controllers_msgs/PointHeadAction.h>
67 #include <pr2_controllers_msgs/QueryTrajectoryState.h>
68 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
73 printf(
"%s % 7.3f % 7.3f % 7.3f\n", label, v.x(), v.y(), v.z() );
139 nh_.
advertise<trajectory_msgs::JointTrajectory>(
"command", 2);
143 nh_.
serviceClient<pr2_controllers_msgs::QueryTrajectoryState>(
"/head_traj_controller/query_state");
146 if(
tree_.getNrOfJoints() == 0)
148 std::string robot_desc_string;
149 nh_.
param(
"/robot_description", robot_desc_string, std::string());
150 ROS_DEBUG(
"Reading tree from robot_description...");
152 ROS_ERROR(
"Failed to construct kdl tree");
156 ROS_ERROR(
"Failed to parse urdf string for urdf::Model.");
161 ROS_DEBUG(
"Tree has %d joints and %d segments.",
tree_.getNrOfJoints(),
tree_.getNrOfSegments());
173 for (
int i = 0; i < 10; ++i)
194 const geometry_msgs::PointStamped &target = gh.getGoal()->target;
208 std::string error_msg;
216 if (found != std::string::npos)
218 ROS_WARN(
"Pointing axis appears to be zero-length. Using [0, 0, 1] as default for an optical frame.");
223 ROS_WARN(
"Pointing axis appears to be zero-length. Using [1, 0, 0] as default for a non-optical frame.");
234 ROS_ERROR(
"Transform failure (%d): %s", ret1, ex.what());
244 std::string error_msg;
248 geometry_msgs::PointStamped target_in_root_msg;
254 ROS_ERROR(
"Transform failure (%d): %s", ret1, ex.what());
275 unsigned int joints =
chain_.getNrOfJoints();
286 KDL::JntArray jnt_pos(joints), jnt_eff(joints);
287 KDL::Jacobian jacobian(joints);
289 pr2_controllers_msgs::QueryTrajectoryState traj_state;
293 ROS_ERROR(
"Service call to query controller trajectory failed.");
297 if(traj_state.response.name.size() != joints)
299 ROS_ERROR(
"Number of joints mismatch: urdf chain vs. trajectory controller state.");
303 std::vector<urdf::JointLimits> limits_(joints);
306 for(
unsigned int i = 0; i < joints; i++)
310 ROS_DEBUG(
"Joint %d %s: %f, limits: %f %f", i, traj_state.response.name[i].c_str(), traj_state.response.position[i], limits_[i].lower, limits_[i].upper);
317 float correction_angle = 2*M_PI;
318 float correction_delta = 2*M_PI;
319 while(
ros::ok() && fabs(correction_delta) > 0.001)
331 tf::Vector3 current_in_frame = frame_in_root.
getBasis().
inverse()*target_from_frame;
332 float prev_correction = correction_angle;
333 correction_angle = current_in_frame.angle(axis_in_frame);
334 correction_delta = correction_angle - prev_correction;
335 ROS_DEBUG(
"At step %d, joint poses are %.4f and %.4f, angle error is %f", count, jnt_pos(0), jnt_pos(1), correction_angle);
337 tf::Vector3 correction_axis = frame_in_root.
getBasis()*(axis_in_frame.cross(current_in_frame).normalized());
340 KDL::Frame correction_kdl;
344 KDL::Frame identity_kdl;
345 KDL::Twist twist = diff(correction_kdl, identity_kdl);
346 KDL::Wrench wrench_desi;
347 for (
unsigned int i=0; i<6; i++)
348 wrench_desi(i) = -1.0*twist(i);
351 for (
unsigned int i = 0; i < joints; i++)
354 for (
unsigned int j=0; j<6; j++)
355 jnt_eff(i) += (jacobian(j,i) * wrench_desi(j));
356 jnt_pos(i) += jnt_eff(i);
360 if(jnt_pos(0) < limits_[0].lower && limit_flips++ == 0){ jnt_pos(0) += 1.5*M_PI; }
361 if(jnt_pos(0) > limits_[0].upper && limit_flips++ == 0){ jnt_pos(0) -= 1.5*M_PI; }
363 jnt_pos(1) = std::max(limits_[1].lower, jnt_pos(1));
364 jnt_pos(1) = std::min(limits_[1].upper, jnt_pos(1));
369 ROS_ERROR(
"Goal is out of joint limits, trying to point there anyway... \n");
373 ROS_DEBUG(
"Iterative solver took %d steps", count);
375 std::vector<double> q_goal(joints);
377 for(
unsigned int i = 0; i < joints; i++)
379 jnt_pos(i) = std::max(limits_[i].lower, jnt_pos(i));
380 jnt_pos(i) = std::min(limits_[i].upper, jnt_pos(i));
381 q_goal[i] = jnt_pos(i);
399 if (gh.getGoal()->min_duration > min_duration)
400 min_duration = gh.getGoal()->min_duration;
403 if (gh.getGoal()->max_velocity > 0)
406 double dist = sqrt(pow(q_goal[0] - traj_state.response.position[0], 2) +
407 pow(q_goal[1] - traj_state.response.position[1], 2));
408 ros::Duration limit_from_velocity(dist / gh.getGoal()->max_velocity);
409 if (limit_from_velocity > min_duration)
410 min_duration = limit_from_velocity;
415 trajectory_msgs::JointTrajectory traj;
416 traj.header.stamp = traj_state.request.time;
418 traj.joint_names.push_back(traj_state.response.name[0]);
419 traj.joint_names.push_back(traj_state.response.name[1]);
421 traj.points.resize(2);
422 traj.points[0].positions = traj_state.response.position;
423 traj.points[0].velocities = traj_state.response.velocity;
425 traj.points[1].positions = q_goal;
426 traj.points[1].velocities.push_back(0);
427 traj.points[1].velocities.push_back(0);
428 traj.points[1].time_from_start =
ros::Duration(min_duration);
441 bool should_abort =
false;
445 ROS_WARN(
"Aborting goal because we have never heard a controller state message.");
450 ROS_WARN(
"Aborting goal because we haven't heard from the controller in %.3lf seconds",
457 trajectory_msgs::JointTrajectory empty;
474 trajectory_msgs::JointTrajectory empty;
496 KDL::JntArray jnt_pos(msg->joint_names.size());
497 for(
unsigned int i = 0; i < msg->joint_names.size(); i++)
498 jnt_pos(i) = msg->actual.positions[i];
509 target_from_frame.normalize();
510 tf::Vector3 current_in_frame = frame_in_root.
getBasis().
inverse()*target_from_frame;
512 pr2_controllers_msgs::PointHeadFeedback feedback;
513 feedback.pointing_angle_error = current_in_frame.angle(axis_in_frame);
524 ROS_ERROR(
"Could not transform: %s", ex.what());
531 int main(
int argc,
char** argv)
533 ros::init(argc, argv,
"point_head_action");