41 #include <pr2_controllers_msgs/QueryTrajectoryState.h> 42 #include <pr2_controllers_msgs/JointTrajectoryAction.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> 68 std::string xml_string;
69 if (!nh_toplevel.
getParam(std::string(
"robot_description"), xml_string))
71 ROS_ERROR(
"Could not find parameter robot_description on parameter server.");
127 ROS_DEBUG(
"%s: Waiting for %s action server to come up",
action_name_.c_str(), trajectory_action_name.c_str());
131 ROS_ERROR(
"%s: %s action server took too long to start",
action_name_.c_str(), trajectory_action_name.c_str());
154 void executeCB(
const pr2_common_action_msgs::ArmMoveIKGoalConstPtr & goal)
162 if (goal->tool_frame.header.frame_id ==
"")
169 geometry_msgs::PoseStamped tip_to_tool_msg;
176 ROS_ERROR(
"Failed to transform tool_frame into \"%s\": %s",
tip_name_.c_str(), ex.what());
186 geometry_msgs::PoseStamped root_to_tool_goal_msg;
203 KDL::Frame desired_pose;
204 tf::PoseTFToKDL(root_to_tip_goal, desired_pose);
208 ROS_ERROR(
"The goal ik_seed must be size %d but is size %lu",
dimension_, goal->ik_seed.name.size());
219 std::vector<KDL::JntArray> jnt_pos_out;
223 ROS_ERROR(
"%s: Aborted: IK invalid. Cannot get to (%.3f,%.3f,%.3f)(%.2f,%.2f,%.2f,%.2f)",
action_name_.c_str(),
231 std::vector<double> traj_desired(dimension_);
232 std::vector<std::string> traj_names(dimension_);
236 traj_names[i] = goal->ik_seed.name[i];
237 traj_desired[i] = jnt_pos_out[0](
getJointIndex(goal->ik_seed.name[i]));
240 pr2_controllers_msgs::JointTrajectoryGoal traj_goal ;
241 std::vector<double> velocities(dimension_, 0.0);
243 traj_goal.trajectory.points.resize(1);
244 traj_goal.trajectory.joint_names = traj_names;
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;
273 if(
kdl_chain_.getSegment(i).getJoint().getType() == KDL::Joint::None)
278 if(
kdl_chain_.getSegment(i).getJoint().getName() == name)
307 pr2_common_action_msgs::ArmMoveIKResult
result_;
311 int main(
int argc,
char** argv)
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
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)
tf::TransformListener tf_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ROSCPP_DECL void spin(Spinner &spinner)
std::string joint_action_
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void registerPreemptCallback(boost::function< void()> cb)
ArmMoveIKAction(std::string name)
boost::shared_ptr< pr2_arm_kinematics::PR2ArmIKSolver > pr2_arm_ik_solver_
void executeCB(const pr2_common_action_msgs::ArmMoveIKGoalConstPtr &goal)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
std::string arm_controller_
int getJointIndex(const std::string &name)
double search_discretization_
bool getParam(const std::string &key, std::string &s) const
ROSCPP_DECL void shutdown()
pr2_common_action_msgs::ArmMoveIKResult result_
SimpleClientGoalState getState() const
KDL::JntArray jnt_pos_suggestion_
actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > * trajectory_action_
actionlib::SimpleActionServer< pr2_common_action_msgs::ArmMoveIKAction > as_