moveit2
The MoveIt Motion Planning Framework for ROS 2.
pose_tracking.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, PickNik Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 /*
35  Author: Andy Zelenak
36  Desc: Servoing. Track a pose setpoint in real time.
37 */
38 
39 #pragma once
40 
41 #include <atomic>
42 #include <control_toolbox/pid.hpp>
45 #include <moveit_servo/servo.h>
46 #include <optional>
47 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
48 #include <tf2_ros/transform_listener.h>
49 #include <rclcpp/rclcpp.hpp>
50 
51 // Conventions:
52 // Calculations are done in the planning_frame_ unless otherwise noted.
53 
54 namespace moveit_servo
55 {
56 struct PIDConfig
57 {
58  // Default values
59  double dt = 0.001;
60  double k_p = 1;
61  double k_i = 0;
62  double k_d = 0;
63  double windup_limit = 0.1;
64 };
65 
66 enum class PoseTrackingStatusCode : int8_t
67 {
68  INVALID = -1,
69  SUCCESS = 0,
72  STOP_REQUESTED = 3
73 };
74 
75 const std::unordered_map<PoseTrackingStatusCode, std::string> POSE_TRACKING_STATUS_CODE_MAP(
76  { { PoseTrackingStatusCode::INVALID, "Invalid" },
77  { PoseTrackingStatusCode::SUCCESS, "Success" },
78  { PoseTrackingStatusCode::NO_RECENT_TARGET_POSE, "No recent target pose" },
79  { PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE, "No recent end effector pose" },
80  { PoseTrackingStatusCode::STOP_REQUESTED, "Stop requested" } });
81 
87 {
88 public:
90  PoseTracking(const rclcpp::Node::SharedPtr& node, const ServoParameters::SharedConstPtr& servo_parameters,
91  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
92 
93  PoseTrackingStatusCode moveToPose(const Eigen::Vector3d& positional_tolerance, const double angular_tolerance,
94  const double target_pose_timeout);
95 
97  void stopMotion();
98 
100  void updatePIDConfig(const double x_proportional_gain, const double x_integral_gain, const double x_derivative_gain,
101  const double y_proportional_gain, const double y_integral_gain, const double y_derivative_gain,
102  const double z_proportional_gain, const double z_integral_gain, const double z_derivative_gain,
103  const double angular_proportional_gain, const double angular_integral_gain,
104  const double angular_derivative_gain);
105 
106  void getPIDErrors(double& x_error, double& y_error, double& z_error, double& orientation_error);
107 
115  bool getCommandFrameTransform(geometry_msgs::msg::TransformStamped& transform);
116 
118  void resetTargetPose();
119 
120  // moveit_servo::Servo instance. Public so we can access member functions like setPaused()
121  std::unique_ptr<moveit_servo::Servo> servo_;
122 
123 private:
125  void readROSParams();
126 
128  void initializePID(const PIDConfig& pid_config, std::vector<control_toolbox::Pid>& pid_vector);
129 
131  bool haveRecentTargetPose(const double timeout);
132 
134  bool haveRecentEndEffectorPose(const double timeout);
135 
137  bool satisfiesPoseTolerance(const Eigen::Vector3d& positional_tolerance, const double angular_tolerance);
138 
140  void targetPoseCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg);
141 
143  void updateControllerSetpoints();
144 
146  void updateControllerStateMeasurements();
147 
149  geometry_msgs::msg::TwistStamped::ConstSharedPtr calculateTwistCommand();
150 
152  void doPostMotionReset();
153 
154  rclcpp::Node::SharedPtr node_;
156 
157  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
158  moveit::core::RobotModelConstPtr robot_model_;
159  // Joint group used for controlling the motions
160  std::string move_group_name_;
161 
162  rclcpp::WallRate loop_rate_;
163 
164  // ROS interface to Servo
165  rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr twist_stamped_pub_;
166 
167  std::vector<control_toolbox::Pid> cartesian_position_pids_;
168  std::vector<control_toolbox::Pid> cartesian_orientation_pids_;
169  // Cartesian PID configs
170  PIDConfig x_pid_config_, y_pid_config_, z_pid_config_, angular_pid_config_;
171 
172  // Transforms w.r.t. planning_frame_
173  Eigen::Isometry3d command_frame_transform_;
174  rclcpp::Time command_frame_transform_stamp_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
175  geometry_msgs::msg::PoseStamped target_pose_;
176  mutable std::mutex target_pose_mtx_;
177 
178  // Subscribe to target pose
179  rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr target_pose_sub_;
180 
181  tf2_ros::Buffer transform_buffer_;
182  tf2_ros::TransformListener transform_listener_;
183 
184  // Expected frame name, for error checking and transforms
185  std::string planning_frame_;
186 
187  // Flag that a different thread has requested a stop.
188  std::atomic<bool> stop_requested_;
189 
190  std::optional<double> angular_error_;
191 };
192 
193 // using alias
194 using PoseTrackingPtr = std::shared_ptr<PoseTracking>;
195 } // namespace moveit_servo
void getPIDErrors(double &x_error, double &y_error, double &z_error, double &orientation_error)
PoseTrackingStatusCode moveToPose(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance, const double target_pose_timeout)
PoseTracking(const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr &servo_parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Constructor. Loads ROS parameters under the given namespace.
std::unique_ptr< moveit_servo::Servo > servo_
bool getCommandFrameTransform(geometry_msgs::msg::TransformStamped &transform)
void stopMotion()
A method for a different thread to stop motion and return early from control loop.
void resetTargetPose()
Re-initialize the target pose to an empty message. Can be used to reset motion between waypoints.
void updatePIDConfig(const double x_proportional_gain, const double x_integral_gain, const double x_derivative_gain, const double y_proportional_gain, const double y_integral_gain, const double y_derivative_gain, const double z_proportional_gain, const double z_integral_gain, const double z_derivative_gain, const double angular_proportional_gain, const double angular_integral_gain, const double angular_derivative_gain)
Change PID parameters. Motion is stopped before the update.
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" } })
std::shared_ptr< PoseTracking > PoseTrackingPtr
std::shared_ptr< const ServoParameters > SharedConstPtr