moveit2
The MoveIt Motion Planning Framework for ROS 2.
pose_tracking_demo.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : pose_tracking_example.cpp
3  * Project : moveit_servo
4  * Created : 09/04/2020
5  * Author : Adam Pettinger
6  *
7  * BSD 3-Clause License
8  *
9  * Copyright (c) 2019, Los Alamos National Security, LLC
10  * All rights reserved.
11  *
12  * Redistribution and use in source and binary forms, with or without
13  * modification, are permitted provided that the following conditions are met:
14  *
15  * * Redistributions of source code must retain the above copyright notice, this
16  * list of conditions and the following disclaimer.
17  *
18  * * Redistributions in binary form must reproduce the above copyright notice,
19  * this list of conditions and the following disclaimer in the documentation
20  * and/or other materials provided with the distribution.
21  *
22  * * Neither the name of the copyright holder nor the names of its
23  * contributors may be used to endorse or promote products derived from
24  * this software without specific prior written permission.
25  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
27  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
28  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
29  * ARE
30  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
31  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
32  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
33  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
34  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
35  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
36  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
37  *******************************************************************************/
38 
39 #include <std_msgs/msg/int8.hpp>
40 #include <geometry_msgs/msg/transform_stamped.hpp>
41 
42 #include <moveit_servo/servo.h>
48 #include <thread>
49 
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.pose_tracking_demo");
51 
52 // Class for monitoring status of moveit_servo
54 {
55 public:
56  StatusMonitor(const rclcpp::Node::SharedPtr& node, const std::string& topic)
57  {
58  sub_ = node->create_subscription<std_msgs::msg::Int8>(topic, rclcpp::SystemDefaultsQoS(),
59  [this](const std_msgs::msg::Int8::ConstSharedPtr& msg) {
60  return statusCB(msg);
61  });
62  }
63 
64 private:
65  void statusCB(const std_msgs::msg::Int8::ConstSharedPtr& msg)
66  {
67  moveit_servo::StatusCode latest_status = static_cast<moveit_servo::StatusCode>(msg->data);
68  if (latest_status != status_)
69  {
70  status_ = latest_status;
71  const auto& status_str = moveit_servo::SERVO_STATUS_CODE_MAP.at(status_);
72  RCLCPP_INFO_STREAM(LOGGER, "Servo status: " << status_str);
73  }
74  }
75 
77  rclcpp::Subscription<std_msgs::msg::Int8>::SharedPtr sub_;
78 };
79 
85 int main(int argc, char** argv)
86 {
87  rclcpp::init(argc, argv);
88  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("pose_tracking_demo");
89 
90  rclcpp::executors::SingleThreadedExecutor executor;
91  executor.add_node(node);
92  std::thread executor_thread([&executor]() { executor.spin(); });
93 
94  auto servo_parameters = moveit_servo::ServoParameters::makeServoParameters(node);
95 
96  if (servo_parameters == nullptr)
97  {
98  RCLCPP_FATAL(LOGGER, "Could not get servo parameters!");
99  exit(EXIT_FAILURE);
100  }
101 
102  // Load the planning scene monitor
103  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor;
104  planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node, "robot_description");
105  if (!planning_scene_monitor->getPlanningScene())
106  {
107  RCLCPP_ERROR_STREAM(LOGGER, "Error in setting up the PlanningSceneMonitor.");
108  exit(EXIT_FAILURE);
109  }
110 
111  planning_scene_monitor->providePlanningSceneService();
112  planning_scene_monitor->startSceneMonitor();
113  planning_scene_monitor->startWorldGeometryMonitor(
116  false /* skip octomap monitor */);
117  planning_scene_monitor->startStateMonitor(servo_parameters->joint_topic);
119 
120  // Wait for Planning Scene Monitor to setup
121  if (!planning_scene_monitor->waitForCurrentRobotState(node->now(), 5.0 /* seconds */))
122  {
123  RCLCPP_ERROR_STREAM(LOGGER, "Error waiting for current robot state in PlanningSceneMonitor.");
124  exit(EXIT_FAILURE);
125  }
126 
127  // Create the pose tracker
128  moveit_servo::PoseTracking tracker(node, servo_parameters, planning_scene_monitor);
129 
130  // Make a publisher for sending pose commands
131  auto target_pose_pub =
132  node->create_publisher<geometry_msgs::msg::PoseStamped>("target_pose", rclcpp::SystemDefaultsQoS());
133 
134  // Subscribe to servo status (and log it when it changes)
135  StatusMonitor status_monitor(node, servo_parameters->status_topic);
136 
137  Eigen::Vector3d lin_tol{ 0.001, 0.001, 0.001 };
138  double rot_tol = 0.01;
139 
140  // Get the current EE transform
141  geometry_msgs::msg::TransformStamped current_ee_tf;
142  tracker.getCommandFrameTransform(current_ee_tf);
143 
144  // Convert it to a Pose
145  geometry_msgs::msg::PoseStamped target_pose;
146  target_pose.header.frame_id = current_ee_tf.header.frame_id;
147  target_pose.pose.position.x = current_ee_tf.transform.translation.x;
148  target_pose.pose.position.y = current_ee_tf.transform.translation.y;
149  target_pose.pose.position.z = current_ee_tf.transform.translation.z;
150  target_pose.pose.orientation = current_ee_tf.transform.rotation;
151 
152  // Modify it a little bit
153  target_pose.pose.position.x += 0.1;
154 
155  // resetTargetPose() can be used to clear the target pose and wait for a new one, e.g. when moving between multiple
156  // waypoints
157  tracker.resetTargetPose();
158 
159  // Publish target pose
160  target_pose.header.stamp = node->now();
161  target_pose_pub->publish(target_pose);
162 
163  // Run the pose tracking in a new thread
164  std::thread move_to_pose_thread([&tracker, &lin_tol, &rot_tol] {
165  moveit_servo::PoseTrackingStatusCode tracking_status =
166  tracker.moveToPose(lin_tol, rot_tol, 0.1 /* target pose timeout */);
167  RCLCPP_INFO_STREAM(LOGGER, "Pose tracker exited with status: "
168  << moveit_servo::POSE_TRACKING_STATUS_CODE_MAP.at(tracking_status));
169  });
170 
171  rclcpp::WallRate loop_rate(50);
172  for (size_t i = 0; i < 500; ++i)
173  {
174  // Modify the pose target a little bit each cycle
175  // This is a dynamic pose target
176  target_pose.pose.position.z += 0.0004;
177  target_pose.header.stamp = node->now();
178  target_pose_pub->publish(target_pose);
179 
180  loop_rate.sleep();
181  }
182 
183  // Make sure the tracker is stopped and clean up
184  move_to_pose_thread.join();
185 
186  // Kill executor thread before shutdown
187  executor.cancel();
188  executor_thread.join();
189 
190  rclcpp::shutdown();
191  return EXIT_SUCCESS;
192 }
StatusMonitor(const rclcpp::Node::SharedPtr &node, const std::string &topic)
PoseTrackingStatusCode moveToPose(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance, const double target_pose_timeout)
bool getCommandFrameTransform(geometry_msgs::msg::TransformStamped &transform)
void resetTargetPose()
Re-initialize the target pose to an empty message. Can be used to reset motion between waypoints.
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
The name of the topic used by default for receiving collision objects in the world.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
const std::unordered_map< PoseTrackingStatusCode, std::string > POSE_TRACKING_STATUS_CODE_MAP({ { PoseTrackingStatusCode::INVALID, "Invalid" }, { PoseTrackingStatusCode::SUCCESS, "Success" }, { PoseTrackingStatusCode::NO_RECENT_TARGET_POSE, "No recent target pose" }, { PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE, "No recent end effector pose" }, { PoseTrackingStatusCode::STOP_REQUESTED, "Stop requested" } })
const std::unordered_map< StatusCode, std::string > SERVO_STATUS_CODE_MAP({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_APPROACHING_SINGULARITY, "Moving closer to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" }, { StatusCode::DECELERATE_FOR_LEAVING_SINGULARITY, "Moving away from a singularity, decelerating" } })
const rclcpp::Logger LOGGER
Definition: async_test.h:31
int main(int argc, char **argv)
static SharedConstPtr makeServoParameters(const rclcpp::Node::SharedPtr &node, const std::string &ns="moveit_servo", bool dynamic_parameters=true)