//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_; }
//this is a pretty general function: // goal contains a desired tool pose; // Cartesian path is planned from current joint state to some joint state that achieves desired tool pose // assume gripper pose is in frame "generic_gripper_frame"; need to transform this to Baxter gripper frame // also, frame_id of this pose needs to get converted to "torso" frame bool ArmMotionInterface::plan_path_current_to_goal_gripper_pose() { ROS_INFO("computing a cartesian trajectory to gripper goal pose"); //ROS_WARN("plan_path_current_to_goal_gripper_pose: goal_gripper_pose_"); goal_gripper_pose_ = cart_goal_.des_pose_gripper; xformUtils.printStampedPose(goal_gripper_pose_); goal_flange_affine_ = xform_gripper_pose_to_affine_flange_wrt_torso(goal_gripper_pose_); ROS_INFO("flange goal"); display_affine(goal_flange_affine_); Vectorq7x1 q_start; q_start = get_jspace_start_(); // choose last cmd, or current joint angles path_is_valid_ = cartTrajPlanner_.cartesian_path_planner(q_start, goal_flange_affine_, optimal_path_); if (path_is_valid_) { baxter_traj_streamer_.stuff_trajectory_right_arm(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 = cartesian_planner::cart_moveResult::SUCCESS; cart_result_.computed_arrival_time = computed_arrival_time_; cart_move_as_.setSucceeded(cart_result_); } else { cart_result_.return_code = cartesian_planner::cart_moveResult::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::plan_path_qstart_to_Agoal(Vectorq7x1 q_start) { // provide q_start; assumes use of a_flange_end_ and fills in g_optimal_path path_is_valid_ = cartTrajPlanner_.cartesian_path_planner(q_start, a_flange_end_, optimal_path_); return path_is_valid_; }