//this is a pretty general function: // goal contains a desired tool pose; // path is planned from current joint state to some joint state that achieves desired tool pose bool ArmMotionInterface::rt_arm_plan_path_current_to_goal_pose() { ROS_INFO("computing a cartesian trajectory to right-arm tool goal pose"); //unpack the goal pose: goal_gripper_pose_right_ = cart_goal_.des_pose_gripper_right; goal_gripper_affine_right_= transformPoseToEigenAffine3d(goal_gripper_pose_right_.pose); ROS_INFO("tool frame goal: "); display_affine(goal_gripper_affine_right_); goal_flange_affine_right_ = goal_gripper_affine_right_ * A_tool_wrt_flange_.inverse(); ROS_INFO("flange goal"); display_affine(goal_flange_affine_right_); Vectorq7x1 q_start; q_start = get_jspace_start_right_arm_(); // choose last cmd, or current joint angles path_is_valid_ = cartTrajPlanner_.cartesian_path_planner(q_start, goal_flange_affine_right_, optimal_path_); if (path_is_valid_) { baxter_traj_streamer_.stuff_trajectory(optimal_path_, des_trajectory_); //convert from vector of poses to trajectory message computed_arrival_time_ = des_trajectory_.points.back().time_from_start.toSec(); cart_result_.return_code = cwru_action::cwru_baxter_cart_moveResult::SUCCESS; cart_result_.computed_arrival_time = computed_arrival_time_; cart_move_as_.setSucceeded(cart_result_); } else { cart_result_.return_code = cwru_action::cwru_baxter_cart_moveResult::RT_ARM_PATH_NOT_VALID; cart_result_.computed_arrival_time = -1.0; //impossible arrival time cart_move_as_.setSucceeded(cart_result_); //the communication was a success, but not the computation } return path_is_valid_; }
bool ArmMotionInterface::rt_arm_plan_path_current_to_goal_dp_xyz() { Eigen::Vector3d dp_vec; ROS_INFO("called rt_arm_plan_path_current_to_goal_dp_xyz"); //unpack the goal pose: int ndim = cart_goal_.arm_dp_right.size(); if (ndim!=3) { ROS_WARN("requested displacement, arm_dp_right, is wrong dimension"); cart_result_.return_code = cwru_action::cwru_baxter_cart_moveResult::RT_ARM_PATH_NOT_VALID; path_is_valid_=false; return path_is_valid_; } for (int i=0;i<3;i++) dp_vec[i] = cart_goal_.arm_dp_right[i]; ROS_INFO("requested dp = %f, %f, %f",dp_vec[0],dp_vec[1],dp_vec[2]); Vectorq7x1 q_start; q_start = get_jspace_start_right_arm_(); // choose last cmd, or current joint angles path_is_valid_= plan_cartesian_delta_p(q_start, dp_vec); if (path_is_valid_) { baxter_traj_streamer_.stuff_trajectory(optimal_path_, des_trajectory_); //convert from vector of poses to trajectory message computed_arrival_time_ = des_trajectory_.points.back().time_from_start.toSec(); cart_result_.return_code = cwru_action::cwru_baxter_cart_moveResult::SUCCESS; cart_result_.computed_arrival_time = computed_arrival_time_; cart_move_as_.setSucceeded(cart_result_); } else { cart_result_.return_code = cwru_action::cwru_baxter_cart_moveResult::RT_ARM_PATH_NOT_VALID; cart_result_.computed_arrival_time = -1.0; //impossible arrival time cart_move_as_.setSucceeded(cart_result_); //the communication was a success, but not the computation } return path_is_valid_; }
//take in q_start and q_end and build trivial path in optimal_path_ for pure joint-space move bool ArmMotionInterface::plan_jspace_path_qstart_to_qend(Vectorq7x1 q_start, Vectorq7x1 q_goal) { ROS_INFO("setting up a joint-space path"); path_is_valid_ = cartTrajPlanner_.jspace_trivial_path_planner(q_start, q_goal, optimal_path_); if (path_is_valid_) { baxter_traj_streamer_.stuff_trajectory(optimal_path_, des_trajectory_); //convert from vector of poses to trajectory message computed_arrival_time_ = des_trajectory_.points.back().time_from_start.toSec(); cart_result_.return_code = cwru_action::cwru_baxter_cart_moveResult::SUCCESS; cart_result_.computed_arrival_time = computed_arrival_time_; cart_move_as_.setSucceeded(cart_result_); } else { cart_result_.return_code = cwru_action::cwru_baxter_cart_moveResult::RT_ARM_PATH_NOT_VALID; cart_result_.computed_arrival_time = -1.0; //impossible arrival time cart_move_as_.setSucceeded(cart_result_); //the communication was a success, but not the computation } return path_is_valid_; }