pose_tracking.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, PickNik LLC
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 LLC 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 <boost/optional.hpp>
43 #include <control_toolbox/pid.h>
45 #include <moveit_servo/servo.h>
49 
50 // Conventions:
51 // Calculations are done in the planning_frame_ unless otherwise noted.
52 
53 namespace moveit_servo
54 {
55 struct PIDConfig
56 {
57  // Default values
58  double dt = 0.001;
59  double k_p = 1;
60  double k_i = 0;
61  double k_d = 0;
62  double windup_limit = 0.1;
63 };
64 
65 enum class PoseTrackingStatusCode : int8_t
66 {
67  INVALID = -1,
68  SUCCESS = 0,
71  STOP_REQUESTED = 3
72 };
73 
74 const std::unordered_map<PoseTrackingStatusCode, std::string> POSE_TRACKING_STATUS_CODE_MAP(
75  { { PoseTrackingStatusCode::INVALID, "Invalid" },
76  { PoseTrackingStatusCode::SUCCESS, "Success" },
77  { PoseTrackingStatusCode::NO_RECENT_TARGET_POSE, "No recent target pose" },
78  { PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE, "No recent end effector pose" },
79  { PoseTrackingStatusCode::STOP_REQUESTED, "Stop requested" } });
80 
85 class PoseTracking
86 {
87 public:
89  PoseTracking(const ros::NodeHandle& nh, const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
90 
91  PoseTrackingStatusCode moveToPose(const Eigen::Vector3d& positional_tolerance, const double angular_tolerance,
92  const double target_pose_timeout);
93 
95  void stopMotion();
96 
98  void updatePIDConfig(const double x_proportional_gain, const double x_integral_gain, const double x_derivative_gain,
99  const double y_proportional_gain, const double y_integral_gain, const double y_derivative_gain,
100  const double z_proportional_gain, const double z_integral_gain, const double z_derivative_gain,
101  const double angular_proportional_gain, const double angular_integral_gain,
102  const double angular_derivative_gain);
103 
104  void getPIDErrors(double& x_error, double& y_error, double& z_error, double& orientation_error);
105 
113  bool getCommandFrameTransform(geometry_msgs::TransformStamped& transform);
114 
116  void resetTargetPose();
117 
118  // moveit_servo::Servo instance. Public so we can access member functions like setPaused()
119  std::unique_ptr<moveit_servo::Servo> servo_;
120 
121 private:
124 
126  void initializePID(const PIDConfig& pid_config, std::vector<control_toolbox::Pid>& pid_vector);
127 
129  bool haveRecentTargetPose(const double timeout);
130 
132  bool haveRecentEndEffectorPose(const double timeout);
133 
135  bool satisfiesPoseTolerance(const Eigen::Vector3d& positional_tolerance, const double angular_tolerance);
136 
138  void targetPoseCallback(const geometry_msgs::PoseStampedConstPtr& msg);
139 
142 
145 
147  geometry_msgs::TwistStampedConstPtr calculateTwistCommand();
148 
150  void doPostMotionReset();
151 
153 
154  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
155  robot_model::RobotModelConstPtr robot_model_;
157  // Joint group used for controlling the motions
158  std::string move_group_name_;
159 
161 
162  // ROS interface to Servo
164 
165  std::vector<control_toolbox::Pid> cartesian_position_pids_;
166  std::vector<control_toolbox::Pid> cartesian_orientation_pids_;
167  // Cartesian PID configs
169 
170  // Transforms w.r.t. planning_frame_
171  Eigen::Isometry3d command_frame_transform_;
173  geometry_msgs::PoseStamped target_pose_;
174  mutable std::mutex target_pose_mtx_;
175 
176  // Subscribe to target pose
178 
181 
182  // Expected frame name, for error checking and transforms
183  std::string planning_frame_;
184 
185  // Flag that a different thread has requested a stop.
186  std::atomic<bool> stop_requested_;
187 
188  boost::optional<double> angular_error_;
189 };
190 
191 // using alias
192 using PoseTrackingPtr = std::shared_ptr<PoseTracking>;
193 } // namespace moveit_servo
moveit_servo::PIDConfig::k_d
double k_d
Definition: pose_tracking.h:125
moveit_servo::PoseTracking::haveRecentTargetPose
bool haveRecentTargetPose(const double timeout)
Return true if a target pose has been received within timeout [seconds].
Definition: pose_tracking.cpp:207
planning_scene_monitor
moveit_servo::PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE
@ NO_RECENT_END_EFFECTOR_POSE
moveit_servo::PoseTracking::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: pose_tracking.h:186
ros::Publisher
moveit_servo::PoseTracking::haveRecentEndEffectorPose
bool haveRecentEndEffectorPose(const double timeout)
Return true if an end effector pose has been received within timeout [seconds].
Definition: pose_tracking.cpp:213
moveit_servo::PoseTracking::getPIDErrors
void getPIDErrors(double &x_error, double &y_error, double &z_error, double &orientation_error)
Definition: pose_tracking.cpp:366
servo.h
moveit_servo::PoseTrackingStatusCode::NO_RECENT_TARGET_POSE
@ NO_RECENT_TARGET_POSE
moveit_servo::PoseTracking::resetTargetPose
void resetTargetPose()
Re-initialize the target pose to an empty message. Can be used to reset motion between waypoints.
Definition: pose_tracking.cpp:375
moveit_servo::PoseTracking::cartesian_orientation_pids_
std::vector< control_toolbox::Pid > cartesian_orientation_pids_
Definition: pose_tracking.h:198
moveit_servo::PoseTracking::nh_
ros::NodeHandle nh_
Definition: pose_tracking.h:184
moveit_servo::PoseTracking::cartesian_position_pids_
std::vector< control_toolbox::Pid > cartesian_position_pids_
Definition: pose_tracking.h:197
moveit_servo::PIDConfig::k_i
double k_i
Definition: pose_tracking.h:124
moveit_servo::PoseTracking::move_group_name_
std::string move_group_name_
Definition: pose_tracking.h:190
moveit_servo::PoseTracking::y_pid_config_
PIDConfig y_pid_config_
Definition: pose_tracking.h:200
moveit_servo::PoseTracking::target_pose_
geometry_msgs::PoseStamped target_pose_
Definition: pose_tracking.h:205
moveit_servo::PoseTracking::updateControllerSetpoints
void updateControllerSetpoints()
Update PID controller target positions & orientations.
moveit_servo::PIDConfig::windup_limit
double windup_limit
Definition: pose_tracking.h:126
moveit_servo::PoseTracking::command_frame_transform_stamp_
ros::Time command_frame_transform_stamp_
Definition: pose_tracking.h:204
moveit_servo::PoseTrackingStatusCode::SUCCESS
@ SUCCESS
make_shared_from_pool.h
moveit_servo::PoseTracking::doPostMotionReset
void doPostMotionReset()
Reset flags and PID controllers after a motion completes.
Definition: pose_tracking.cpp:320
moveit_servo::PoseTracking::updateControllerStateMeasurements
void updateControllerStateMeasurements()
Update PID controller states (positions & orientations)
moveit_servo::PoseTracking::satisfiesPoseTolerance
bool satisfiesPoseTolerance(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance)
Check if XYZ, roll/pitch/yaw tolerances are satisfied.
Definition: pose_tracking.cpp:218
moveit_servo::PoseTracking::z_pid_config_
PIDConfig z_pid_config_
Definition: pose_tracking.h:200
moveit_servo::PoseTracking::updatePIDConfig
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 udpate.
Definition: pose_tracking.cpp:333
tf2_ros::TransformListener
moveit_servo::PoseTracking::transform_listener_
tf2_ros::TransformListener transform_listener_
Definition: pose_tracking.h:212
moveit_servo::PoseTrackingStatusCode::INVALID
@ INVALID
moveit_servo::PIDConfig::dt
double dt
Definition: pose_tracking.h:122
moveit_servo::PoseTracking::robot_model_
robot_model::RobotModelConstPtr robot_model_
Definition: pose_tracking.h:187
moveit_servo::PoseTracking::calculateTwistCommand
geometry_msgs::TwistStampedConstPtr calculateTwistCommand()
Use PID controllers to calculate a full spatial velocity toward a pose.
Definition: pose_tracking.cpp:258
moveit_servo
Definition: collision_check.h:50
moveit_servo::PoseTrackingPtr
std::shared_ptr< PoseTracking > PoseTrackingPtr
Definition: pose_tracking.h:224
moveit_servo::PoseTrackingStatusCode
PoseTrackingStatusCode
Definition: pose_tracking.h:97
moveit_servo::PoseTracking::command_frame_transform_
Eigen::Isometry3d command_frame_transform_
Definition: pose_tracking.h:203
moveit_servo::PoseTracking::stopMotion
void stopMotion()
A method for a different thread to stop motion and return early from control loop.
Definition: pose_tracking.cpp:306
rosparam_shortcuts.h
tf2_ros::Buffer
moveit_servo::PoseTrackingStatusCode::STOP_REQUESTED
@ STOP_REQUESTED
moveit_servo::PoseTracking::loop_rate_
ros::Rate loop_rate_
Definition: pose_tracking.h:192
moveit_servo::PoseTracking::angular_error_
boost::optional< double > angular_error_
Definition: pose_tracking.h:220
moveit_servo::PoseTracking::x_pid_config_
PIDConfig x_pid_config_
Definition: pose_tracking.h:200
moveit_servo::PoseTracking::twist_stamped_pub_
ros::Publisher twist_stamped_pub_
Definition: pose_tracking.h:195
moveit_servo::PoseTracking::target_pose_mtx_
std::mutex target_pose_mtx_
Definition: pose_tracking.h:206
transform_listener.h
ros::Time
moveit_servo::PIDConfig::k_p
double k_p
Definition: pose_tracking.h:123
moveit::core::JointModelGroup
moveit_servo::PoseTracking::stop_requested_
std::atomic< bool > stop_requested_
Definition: pose_tracking.h:218
tf2_geometry_msgs.h
moveit_servo::PoseTracking::angular_pid_config_
PIDConfig angular_pid_config_
Definition: pose_tracking.h:200
ros::Rate
pid.h
moveit_servo::PoseTracking::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: pose_tracking.h:188
moveit_servo::PoseTracking::moveToPose
PoseTrackingStatusCode moveToPose(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance, const double target_pose_timeout)
Definition: pose_tracking.cpp:79
moveit_servo::PoseTracking::target_pose_sub_
ros::Subscriber target_pose_sub_
Definition: pose_tracking.h:209
moveit_servo::PoseTracking::transform_buffer_
tf2_ros::Buffer transform_buffer_
Definition: pose_tracking.h:211
moveit_servo::PoseTracking::PoseTracking
PoseTracking(const ros::NodeHandle &nh, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Constructor. Loads ROS parameters under the given namespace.
Definition: pose_tracking.cpp:46
moveit_servo::POSE_TRACKING_STATUS_CODE_MAP
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" } })
moveit_servo::PoseTracking::readROSParams
void readROSParams()
Load ROS parameters for controller settings.
Definition: pose_tracking.cpp:144
moveit_servo::PoseTracking::targetPoseCallback
void targetPoseCallback(const geometry_msgs::PoseStampedConstPtr &msg)
Subscribe to the target pose on this topic.
Definition: pose_tracking.cpp:233
moveit_servo::PIDConfig
Definition: pose_tracking.h:87
moveit_servo::PoseTracking::servo_
std::unique_ptr< moveit_servo::Servo > servo_
Definition: pose_tracking.h:151
moveit_servo::PoseTracking::planning_frame_
std::string planning_frame_
Definition: pose_tracking.h:215
ros::NodeHandle
ros::Subscriber
moveit_servo::PoseTracking::initializePID
void initializePID(const PIDConfig &pid_config, std::vector< control_toolbox::Pid > &pid_vector)
Initialize a PID controller and add it to vector of controllers.
Definition: pose_tracking.cpp:200
moveit_servo::PoseTracking::getCommandFrameTransform
bool getCommandFrameTransform(geometry_msgs::TransformStamped &transform)
Definition: pose_tracking.cpp:382
int8_t
int8_t


moveit_servo
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Alexander Rössler , Tyler Weaver
autogenerated on Sat May 3 2025 02:27:56