cpp_interface_example.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : cpp_interface_example.cpp
3  * Project : moveit_servo
4  * Created : 11/20/2019
5  * Author : Andy Zelenak
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 
41 #include <moveit_servo/servo.h>
44 
45 static const std::string LOGNAME = "cpp_interface_example";
46 
47 // Class for monitoring status of moveit_servo
49 {
50 public:
51  StatusMonitor(ros::NodeHandle& nh, const std::string& topic)
52  {
53  sub_ = nh.subscribe(topic, 1, &StatusMonitor::statusCB, this);
54  }
55 
56 private:
57  void statusCB(const std_msgs::Int8ConstPtr& msg)
58  {
59  moveit_servo::StatusCode latest_status = static_cast<moveit_servo::StatusCode>(msg->data);
60  if (latest_status != status_)
61  {
62  status_ = latest_status;
63  const auto& status_str = moveit_servo::SERVO_STATUS_CODE_MAP.at(status_);
64  ROS_INFO_STREAM_NAMED(LOGNAME, "Servo status: " << status_str);
65  }
66  }
69 };
70 
75 int main(int argc, char** argv)
76 {
77  ros::init(argc, argv, LOGNAME);
78  ros::NodeHandle nh("~");
80  spinner.start();
81 
82  // Load the planning scene monitor
83  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor;
84  planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
85  if (!planning_scene_monitor->getPlanningScene())
86  {
87  ROS_ERROR_STREAM_NAMED(LOGNAME, "Error in setting up the PlanningSceneMonitor.");
88  exit(EXIT_FAILURE);
89  }
90 
91  planning_scene_monitor->startSceneMonitor();
92  planning_scene_monitor->startWorldGeometryMonitor(
95  false /* skip octomap monitor */);
96  planning_scene_monitor->startStateMonitor();
97 
98  // Run the servo node C++ interface in a new timer to ensure a constant outgoing message rate.
100  servo.start();
101 
102  // Subscribe to servo status (and log it when it changes)
103  StatusMonitor status_monitor(nh, servo.getParameters().status_topic);
104 
105  // Create publishers to send servo commands
106  auto twist_stamped_pub =
107  nh.advertise<geometry_msgs::TwistStamped>(servo.getParameters().cartesian_command_in_topic, 1);
108  auto joint_servo_pub = nh.advertise<control_msgs::JointJog>(servo.getParameters().joint_command_in_topic, 1);
109 
110  ros::Rate cmd_rate(100);
111  uint num_commands = 0;
112 
113  // Send a few Cartesian velocity commands
114  while (ros::ok() && num_commands < 200)
115  {
116  // Make a Cartesian velocity message
117  // Messages are sent to servo node as boost::shared_ptr to enable zero-copy message_passing.
118  // Because this message is not copied we should not modify it after we send it.
119  auto msg = moveit::util::make_shared_from_pool<geometry_msgs::TwistStamped>();
120  msg->header.stamp = ros::Time::now();
121  msg->header.frame_id = "base_link";
122  msg->twist.linear.y = 0.01;
123  msg->twist.linear.z = -0.01;
124 
125  // Send the message
126  twist_stamped_pub.publish(msg);
127  cmd_rate.sleep();
128  ++num_commands;
129  }
130 
131  // Leave plenty of time for the servo node to halt its previous motion.
132  // For a faster response, adjust the incoming_command_timeout yaml parameter
133  ros::Duration(2).sleep();
134 
135  // Send a few joint commands
136  num_commands = 0;
137  while (ros::ok() && num_commands < 200)
138  {
139  // Make a joint command
140  // Messages are sent to servo node as boost::shared_ptr to enable zero-copy message_passing.
141  // Because this message is not copied we should not modify it after we send it.
142  auto msg = moveit::util::make_shared_from_pool<control_msgs::JointJog>();
143  msg->header.stamp = ros::Time::now();
144  msg->joint_names.push_back("elbow_joint");
145  msg->velocities.push_back(0.2);
146 
147  // Send the message
148  joint_servo_pub.publish(msg);
149  cmd_rate.sleep();
150  ++num_commands;
151  }
152 
153  servo.setPaused(true);
154  return 0;
155 }
planning_scene_monitor
servo.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::AsyncSpinner
moveit_servo::Servo::setPaused
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
Definition: servo.cpp:311
StatusMonitor::statusCB
void statusCB(const std_msgs::Int8ConstPtr &msg)
Definition: cpp_interface_example.cpp:57
moveit_servo::Servo::getParameters
const ServoParameters & getParameters() const
Get the parameters used by servo node.
Definition: servo.cpp:337
moveit_servo::ServoParameters::joint_command_in_topic
std::string joint_command_in_topic
Definition: servo_parameters.h:93
make_shared_from_pool.h
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
moveit_servo::ServoParameters::status_topic
std::string status_topic
Definition: servo_parameters.h:92
ros::ok
ROSCPP_DECL bool ok()
StatusMonitor::StatusMonitor
StatusMonitor(ros::NodeHandle &nh, const std::string &topic)
Definition: cpp_interface_example.cpp:51
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
StatusMonitor
Definition: cpp_interface_example.cpp:48
moveit_servo::ServoParameters::cartesian_command_in_topic
std::string cartesian_command_in_topic
Definition: servo_parameters.h:87
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" } })
LOGNAME
static const std::string LOGNAME
Definition: cpp_interface_example.cpp:45
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
ros::Rate
ros::Duration::sleep
bool sleep() const
ros::Duration
main
int main(int argc, char **argv)
Definition: cpp_interface_example.cpp:75
ros::NodeHandle
ros::Subscriber
moveit_servo::Servo::start
void start()
start servo node
Definition: servo.cpp:294
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::Servo
Definition: servo.h:90


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