arm_ik.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * Author: Melonee Wise
35  *********************************************************************/
36 
37 
38 #include <ros/ros.h>
41 #include <pr2_controllers_msgs/QueryTrajectoryState.h>
42 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
43 #include <tf/transform_listener.h>
44 #include <geometry_msgs/PoseStamped.h>
45 #include <pr2_arm_kinematics/pr2_arm_ik_solver.h>
46 #include <pr2_common_action_msgs/ArmMoveIKAction.h>
47 #include <kdl/frames_io.hpp>
48 #include <urdf/model.h>
49 
51 {
52 
53 public:
54 
55  ArmMoveIKAction(std::string name) :
56  nh_("~"),
57  dimension_(7),
58  action_name_(name),
59  as_(name, boost::bind(&ArmMoveIKAction::executeCB, this, _1))
60  {
61  //register the goal and feeback callbacks
63 
64  ros::NodeHandle nh_toplevel;
65 
66  // Load Robot Model
67  ROS_INFO("%s: Loading robot model", action_name_.c_str());
68  std::string xml_string;
69  if (!nh_toplevel.getParam(std::string("robot_description"), xml_string))
70  {
71  ROS_ERROR("Could not find parameter robot_description on parameter server.");
72  ros::shutdown();
73  exit(1);
74  }
75  if(!robot_model_.initString(xml_string))
76  {
77  ROS_ERROR("Could not load robot model.");
78  ros::shutdown();
79  exit(1);
80  }
81 
82  // Get Parameters
83  nh_.param<std::string>("arm", arm_, "r");
84  nh_.param("joint_trajectory_action", joint_action_, std::string("joint_trajectory_action"));
85  nh_.param("free_angle", free_angle_, 2);
86  nh_.param("search_discretization", search_discretization_, 0.01);
87  nh_.param("ik_timeout", timeout_, 5.0);
88  root_name_ = "torso_lift_link";
89  tip_name_ = arm_ + "_wrist_roll_link";
90 
91 
92  // Init pose suggestion
94 
95  ROS_DEBUG("%s: Loading KDL chain", action_name_.c_str());
96  KDL::Tree tree;
97  if (!kdl_parser::treeFromUrdfModel(robot_model_, tree))
98  {
99  ROS_ERROR("%s: Could not load the KDL tree from the robot model", action_name_.c_str());
100  ros::shutdown();
101  exit(1);
102  }
103  if (!tree.getChain(root_name_, tip_name_, kdl_chain_))
104  {
105  ROS_ERROR("%s: Could not create the KDL chain", action_name_.c_str());
106  ros::shutdown();
107  exit(1);
108  }
109 
110  // Init IK
111  ROS_DEBUG("Starting with search_discretization %f and ik_timeout %f", search_discretization_,timeout_);
112  pr2_arm_ik_solver_.reset(new pr2_arm_kinematics::PR2ArmIKSolver(robot_model_, root_name_, tip_name_, search_discretization_, free_angle_));
113 
114  if(!pr2_arm_ik_solver_->active_)
115  {
116  ROS_ERROR("%s: Could not load pr2 arm IK solver", action_name_.c_str());
117  ros::shutdown();
118  exit(1);
119  }
120 
121  std::string trajectory_action_name = joint_action_;
123 
124  double counter = 0;
126  {
127  ROS_DEBUG("%s: Waiting for %s action server to come up", action_name_.c_str(), trajectory_action_name.c_str());
128  counter++;
129  if(counter > 3)
130  {
131  ROS_ERROR("%s: %s action server took too long to start", action_name_.c_str(), trajectory_action_name.c_str());
132  //set the action state to aborted
133  ros::shutdown();
134  exit(1);
135  }
136  }
137  //Action ready
138  ROS_INFO("%s: Initialized", action_name_.c_str());
139  }
140 
142  {
143  delete trajectory_action_;
144  }
145 
146  void preemptCB()
147  {
148  ROS_INFO("%s: Preempt", action_name_.c_str());
149  // set the action state to preempted
151  as_.setPreempted();
152  }
153 
154  void executeCB(const pr2_common_action_msgs::ArmMoveIKGoalConstPtr & goal)
155  {
156  // accept the new goal
157  ROS_INFO("%s: Accepted Goal", action_name_.c_str() );
158 
159 
160  // Determines the tool frame pose
161  tf::Pose tip_to_tool;
162  if (goal->tool_frame.header.frame_id == "")
163  {
164  tip_to_tool.setIdentity();
165  }
166  else
167  {
168  try {
169  geometry_msgs::PoseStamped tip_to_tool_msg;
170  tf_.waitForTransform(tip_name_, goal->tool_frame.header.frame_id, goal->tool_frame.header.stamp,
171  ros::Duration(5.0));
172  tf_.transformPose(tip_name_, goal->tool_frame, tip_to_tool_msg);
173  tf::poseMsgToTF(tip_to_tool_msg.pose, tip_to_tool);
174  }
175  catch (const tf::TransformException &ex) {
176  ROS_ERROR("Failed to transform tool_frame into \"%s\": %s", tip_name_.c_str(), ex.what());
177  as_.setAborted();
178  return;
179  }
180  }
181 
182  // Transforms the (tool) goal into the root frame
183  tf::Pose root_to_tool_goal;
184  try
185  {
186  geometry_msgs::PoseStamped root_to_tool_goal_msg;
187  tf_.waitForTransform(root_name_, goal->pose.header.frame_id, goal->pose.header.stamp,
188  ros::Duration(5.0));
189  tf_.transformPose(root_name_, goal->pose, root_to_tool_goal_msg);
190  tf::poseMsgToTF(root_to_tool_goal_msg.pose, root_to_tool_goal);
191  }
192  catch (const tf::TransformException &ex)
193  {
194  ROS_ERROR("Failed to transform goal into \"%s\": %s", root_name_.c_str(), ex.what());
195  as_.setAborted();
196  return;
197  }
198 
199  // Determines the goal of the tip from the goal of the tool
200  tf::Pose root_to_tip_goal = root_to_tool_goal * tip_to_tool.inverse();
201 
202  // Converts into KDL
203  KDL::Frame desired_pose;
204  tf::PoseTFToKDL(root_to_tip_goal, desired_pose);
205 
206  if(goal->ik_seed.name.size() < dimension_ )
207  {
208  ROS_ERROR("The goal ik_seed must be size %d but is size %lu",dimension_, goal->ik_seed.name.size());
209  as_.setAborted();
210  return;
211  }
212  // Get the IK seed from the goal
213  for(int i=0; i < dimension_; i++)
214  {
215  jnt_pos_suggestion_(getJointIndex(goal->ik_seed.name[i])) = goal->ik_seed.position[i];
216  }
217 
218  ROS_DEBUG("calling IK solver");
219  std::vector<KDL::JntArray> jnt_pos_out;
220  bool is_valid = (pr2_arm_ik_solver_->CartToJntSearch(jnt_pos_suggestion_, desired_pose, jnt_pos_out, timeout_)>=0);
221  if(!is_valid)
222  {
223  ROS_ERROR("%s: Aborted: IK invalid. Cannot get to (%.3f,%.3f,%.3f)(%.2f,%.2f,%.2f,%.2f)", action_name_.c_str(),
224  root_to_tip_goal.getOrigin()[0], root_to_tip_goal.getOrigin()[1], root_to_tip_goal.getOrigin()[2],
225  root_to_tip_goal.getRotation().x(),root_to_tip_goal.getRotation().y(),root_to_tip_goal.getRotation().z(),root_to_tip_goal.getRotation().w());
226  //set the action state to aborted
227  as_.setAborted();
228  return;
229  }
230 
231  std::vector<double> traj_desired(dimension_);
232  std::vector<std::string> traj_names(dimension_);
233 
234  for(int i=0; i < dimension_; i++)
235  {
236  traj_names[i] = goal->ik_seed.name[i];
237  traj_desired[i] = jnt_pos_out[0](getJointIndex(goal->ik_seed.name[i]));
238  }
239 
240  pr2_controllers_msgs::JointTrajectoryGoal traj_goal ;
241  std::vector<double> velocities(dimension_, 0.0);
242  traj_goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(0.03);
243  traj_goal.trajectory.points.resize(1);
244  traj_goal.trajectory.joint_names = traj_names;
245 
246  traj_goal.trajectory.points[0].positions = traj_desired;
247  traj_goal.trajectory.points[0].velocities = velocities;
248  traj_goal.trajectory.points[0].time_from_start = goal->move_duration;
249 
250  // Send goal
251  trajectory_action_->sendGoal(traj_goal);
254  {
255  ROS_ERROR("%s: Aborted: trajectory action failed to achieve goal", action_name_.c_str());
256  //set the action state to aborted
258  return;
259  }
260 
261  ROS_INFO("%s: Succeeded", action_name_.c_str());
262  // set the action state to succeeded
264  }
265 
266 
267  int getJointIndex(const std::string &name)
268  {
269  int i=0; // segment number
270  int j=0; // joint number
271  while(j < dimension_ && i < (int) kdl_chain_.getNrOfSegments())
272  {
273  if(kdl_chain_.getSegment(i).getJoint().getType() == KDL::Joint::None)
274  {
275  i++;
276  continue;
277  }
278  if(kdl_chain_.getSegment(i).getJoint().getName() == name)
279  {
280  return j;
281  }
282  i++;
283  j++;
284  }
285  return -1;
286  }
287 
288 
289 protected:
290 
293  std::string joint_action_;
297 
298  KDL::Chain kdl_chain_;
299  KDL::JntArray jnt_pos_suggestion_;
300 
303 
306 
307  pr2_common_action_msgs::ArmMoveIKResult result_;
308 
309 };
310 
311 int main(int argc, char** argv)
312 {
313  ros::init(argc, argv, "pr2_arm_ik");
314 
316  ros::spin();
317 
318  return 0;
319 }
~ArmMoveIKAction(void)
Definition: arm_ik.cpp:141
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
KDL::Chain kdl_chain_
Definition: arm_ik.cpp:298
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
URDF_EXPORT bool initString(const std::string &xmlstring)
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
int main(int argc, char **argv)
Definition: arm_ik.cpp:311
urdf::Model robot_model_
Definition: arm_ik.cpp:292
tf::TransformListener tf_
Definition: arm_ik.cpp:305
std::string root_name_
Definition: arm_ik.cpp:296
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ROSCPP_DECL void spin(Spinner &spinner)
void setIdentity()
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
std::string joint_action_
Definition: arm_ik.cpp:293
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string action_name_
Definition: arm_ik.cpp:296
std::string arm_
Definition: arm_ik.cpp:296
void registerPreemptCallback(boost::function< void()> cb)
double timeout_
Definition: arm_ik.cpp:295
Transform inverse() const
ArmMoveIKAction(std::string name)
Definition: arm_ik.cpp:55
boost::shared_ptr< pr2_arm_kinematics::PR2ArmIKSolver > pr2_arm_ik_solver_
Definition: arm_ik.cpp:304
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void executeCB(const pr2_common_action_msgs::ArmMoveIKGoalConstPtr &goal)
Definition: arm_ik.cpp:154
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void preemptCB()
Definition: arm_ik.cpp:146
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
std::string arm_controller_
Definition: arm_ik.cpp:296
std::string tip_name_
Definition: arm_ik.cpp:296
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
Quaternion getRotation() const
int getJointIndex(const std::string &name)
Definition: arm_ik.cpp:267
double search_discretization_
Definition: arm_ik.cpp:295
bool getParam(const std::string &key, std::string &s) const
static Time now()
ROSCPP_DECL void shutdown()
pr2_common_action_msgs::ArmMoveIKResult result_
Definition: arm_ik.cpp:307
SimpleClientGoalState getState() const
ros::NodeHandle nh_
Definition: arm_ik.cpp:291
KDL::JntArray jnt_pos_suggestion_
Definition: arm_ik.cpp:299
#define ROS_ERROR(...)
actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > * trajectory_action_
Definition: arm_ik.cpp:302
actionlib::SimpleActionServer< pr2_common_action_msgs::ArmMoveIKAction > as_
Definition: arm_ik.cpp:301
#define ROS_DEBUG(...)


pr2_arm_move_ik
Author(s): Wim Meeusen, Melonee Wise
autogenerated on Fri Jun 7 2019 22:06:41