Skip to content

Commit

Permalink
Explicitly set orientations in poses
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Jul 31, 2023
1 parent 443b22d commit 9a96b13
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,7 @@ Open ``mtc_node.cpp`` in your editor of choice, and paste in the following code.
geometry_msgs::msg::Pose pose;
pose.position.x = 0.5;
pose.position.y = -0.25;
pose.orientation.w = 1.0;
object.pose = pose;

moveit::planning_interface::PlanningSceneInterface psi;
Expand Down Expand Up @@ -826,6 +827,7 @@ We then create a ``ComputeIK`` stage and pass it our ``GeneratePlacePose`` stage
geometry_msgs::msg::PoseStamped target_pose_msg;
target_pose_msg.header.frame_id = "object";
target_pose_msg.pose.position.y = 0.5;
target_pose_msg.pose.orientation.w = 1.0;
stage->setPose(target_pose_msg);
stage->setMonitoredStage(attach_object_stage); // Hook into attach_object_stage

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ void MTCTaskNode::setupPlanningScene()
geometry_msgs::msg::Pose pose;
pose.position.x = 0.5;
pose.position.y = -0.25;
pose.orientation.w = 1.0;
object.pose = pose;

moveit::planning_interface::PlanningSceneInterface psi;
Expand Down Expand Up @@ -287,6 +288,7 @@ mtc::Task MTCTaskNode::createTask()
geometry_msgs::msg::PoseStamped target_pose_msg;
target_pose_msg.header.frame_id = "object";
target_pose_msg.pose.position.y = 0.5;
target_pose_msg.pose.orientation.w = 1.0;
stage->setPose(target_pose_msg);
stage->setMonitoredStage(attach_object_stage); // Hook into attach_object_stage

Expand Down

0 comments on commit 9a96b13

Please sign in to comment.