pose_tracking_example.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/Int8.h>
40 #include <geometry_msgs/TransformStamped.h>
41 
42 #include <moveit_servo/servo.h>
46 #include <thread>
47 
48 static const std::string LOGNAME = "cpp_interface_example";
49 
50 // Class for monitoring status of moveit_servo
51 class StatusMonitor
52 {
53 public:
54  StatusMonitor(ros::NodeHandle& nh, const std::string& topic)
55  {
56  sub_ = nh.subscribe(topic, 1, &StatusMonitor::statusCB, this);
57  }
58 
59 private:
60  void statusCB(const std_msgs::Int8ConstPtr& msg)
61  {
62  moveit_servo::StatusCode latest_status = static_cast<moveit_servo::StatusCode>(msg->data);
63  if (latest_status != status_)
64  {
65  status_ = latest_status;
66  const auto& status_str = moveit_servo::SERVO_STATUS_CODE_MAP.at(status_);
67  ROS_INFO_STREAM_NAMED(LOGNAME, "Servo status: " << status_str);
68  }
69  }
72 };
73 
79 int main(int argc, char** argv)
80 {
81  ros::init(argc, argv, LOGNAME);
82  ros::NodeHandle nh("~");
84  spinner.start();
85 
86  // Load the planning scene monitor
87  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor;
88  planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
89  if (!planning_scene_monitor->getPlanningScene())
90  {
91  ROS_ERROR_STREAM_NAMED(LOGNAME, "Error in setting up the PlanningSceneMonitor.");
92  exit(EXIT_FAILURE);
93  }
94 
95  planning_scene_monitor->startSceneMonitor();
96  planning_scene_monitor->startWorldGeometryMonitor(
99  false /* skip octomap monitor */);
100  planning_scene_monitor->startStateMonitor();
101 
102  // Create the pose tracker
104 
105  // Make a publisher for sending pose commands
106  ros::Publisher target_pose_pub =
107  nh.advertise<geometry_msgs::PoseStamped>("target_pose", 1 /* queue */, true /* latch */);
108 
109  // Subscribe to servo status (and log it when it changes)
110  StatusMonitor status_monitor(nh, "status");
111 
112  Eigen::Vector3d lin_tol{ 0.01, 0.01, 0.01 };
113  double rot_tol = 0.1;
114 
115  // Get the current EE transform
116  geometry_msgs::TransformStamped current_ee_tf;
117  tracker.getCommandFrameTransform(current_ee_tf);
118 
119  // Convert it to a Pose
120  geometry_msgs::PoseStamped target_pose;
121  target_pose.header.frame_id = current_ee_tf.header.frame_id;
122  target_pose.pose.position.x = current_ee_tf.transform.translation.x;
123  target_pose.pose.position.y = current_ee_tf.transform.translation.y;
124  target_pose.pose.position.z = current_ee_tf.transform.translation.z;
125  target_pose.pose.orientation = current_ee_tf.transform.rotation;
126 
127  // Modify it a little bit
128  target_pose.pose.position.x += 0.1;
129 
130  // resetTargetPose() can be used to clear the target pose and wait for a new one, e.g. when moving between multiple
131  // waypoints
132  tracker.resetTargetPose();
133 
134  // Publish target pose
135  target_pose.header.stamp = ros::Time::now();
136  target_pose_pub.publish(target_pose);
137 
138  // Run the pose tracking in a new thread
139  std::thread move_to_pose_thread(
140  [&tracker, &lin_tol, &rot_tol] { tracker.moveToPose(lin_tol, rot_tol, 0.1 /* target pose timeout */); });
141 
142  ros::Rate loop_rate(50);
143  for (size_t i = 0; i < 500; ++i)
144  {
145  // Modify the pose target a little bit each cycle
146  // This is a dynamic pose target
147  target_pose.pose.position.z += 0.0004;
148  target_pose.header.stamp = ros::Time::now();
149  target_pose_pub.publish(target_pose);
150 
151  loop_rate.sleep();
152  }
153 
154  // Make sure the tracker is stopped and clean up
155  tracker.stopMotion();
156  move_to_pose_thread.join();
157 
158  return EXIT_SUCCESS;
159 }
planning_scene_monitor
ros::Publisher
servo.h
main
int main(int argc, char **argv)
Definition: pose_tracking_example.cpp:79
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
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
ros::AsyncSpinner
StatusMonitor::statusCB
void statusCB(const std_msgs::Int8ConstPtr &msg)
Definition: cpp_interface_example.cpp:57
moveit_servo::PoseTracking
Definition: pose_tracking.h:117
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
make_shared_from_pool.h
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
StatusMonitor::StatusMonitor
StatusMonitor(ros::NodeHandle &nh, const std::string &topic)
Definition: pose_tracking_example.cpp:54
spinner
void spinner()
status_codes.h
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
moveit_servo::StatusCode
StatusCode
Definition: status_codes.h:82
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_COLLISION_OBJECT_TOPIC
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
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
StatusMonitor
Definition: cpp_interface_example.cpp:48
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
moveit_servo::StatusCode::INVALID
@ INVALID
moveit_servo::SERVO_STATUS_CODE_MAP
const std::unordered_map< StatusCode, std::string > SERVO_STATUS_CODE_MAP({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_SINGULARITY, "Close 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" } })
pose_tracking.h
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
ros::Rate
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
LOGNAME
static const std::string LOGNAME
Definition: pose_tracking_example.cpp:48
ros::NodeHandle
ros::Subscriber
StatusMonitor::status_
moveit_servo::StatusCode status_
Definition: cpp_interface_example.cpp:67
StatusMonitor::sub_
ros::Subscriber sub_
Definition: cpp_interface_example.cpp:68
ros::Time::now
static Time now()
moveit_servo::PoseTracking::getCommandFrameTransform
bool getCommandFrameTransform(geometry_msgs::TransformStamped &transform)
Definition: pose_tracking.cpp:382


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