jog_ros_interface.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019, Los Alamos National Security, 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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32 *******************************************************************************/
33 
34 /* Title : jog_ros_interface.cpp
35  * Project : moveit_jog_arm
36  * Created : 3/9/2017
37  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
38  */
39 
40 // Server node for arm jogging with MoveIt.
41 
43 
44 static const std::string LOGNAME = "jog_ros_interface";
45 
46 namespace moveit_jog_arm
47 {
49 // JogROSInterface handles ROS subscriptions and instantiates the worker threads.
50 // One worker thread does the jogging calculations.
51 // Another worker thread does collision checking.
53 
54 // Constructor for the main ROS interface node
56 {
57  ros::NodeHandle nh;
58 
59  // Read ROS parameters, typically from YAML file
60  if (!readParameters(nh))
61  exit(EXIT_FAILURE);
62 
63  // Load the planning scene monitor
64  planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
65  if (!planning_scene_monitor_->getPlanningScene())
66  {
67  ROS_ERROR_STREAM_NAMED(LOGNAME, "Error in setting up the PlanningSceneMonitor.");
68  exit(EXIT_FAILURE);
69  }
70 
71  planning_scene_monitor_->startSceneMonitor();
72  planning_scene_monitor_->startWorldGeometryMonitor(
75  false /* skip octomap monitor */);
76  planning_scene_monitor_->startStateMonitor();
77 
78  // Crunch the numbers in this thread
80 
81  // Check collisions in this thread
84 
85  // ROS subscriptions. Share the data with the worker threads
86  ros::Subscriber cmd_sub =
88  ros::Subscriber joint_jog_cmd_sub =
90  ros::Subscriber joints_sub =
91  nh.subscribe(ros_parameters_.joint_topic, 1, &JogInterfaceBase::jointsCB, dynamic_cast<JogInterfaceBase*>(this));
92 
93  // ROS Server for allowing drift in some dimensions
94  ros::ServiceServer drift_dimensions_server =
95  nh.advertiseService(nh.getNamespace() + "/" + ros::this_node::getName() + "/change_drift_dimensions",
97  // ROS Server for changing the control dimensions
98  ros::ServiceServer dims_server =
99  nh.advertiseService(nh.getNamespace() + "/" + ros::this_node::getName() + "/change_control_dimensions",
101 
102  // Publish freshly-calculated joints to the robot.
103  // Put the outgoing msg in the right format (trajectory_msgs/JointTrajectory or std_msgs/Float64MultiArray).
104  ros::Publisher outgoing_cmd_pub;
105  if (ros_parameters_.command_out_type == "trajectory_msgs/JointTrajectory")
106  outgoing_cmd_pub = nh.advertise<trajectory_msgs::JointTrajectory>(ros_parameters_.command_out_topic, 1);
107  else if (ros_parameters_.command_out_type == "std_msgs/Float64MultiArray")
108  outgoing_cmd_pub = nh.advertise<std_msgs::Float64MultiArray>(ros_parameters_.command_out_topic, 1);
109 
110  // Wait for incoming topics to appear
111  ROS_DEBUG_NAMED(LOGNAME, "Waiting for JointState topic");
112  ros::topic::waitForMessage<sensor_msgs::JointState>(ros_parameters_.joint_topic);
113 
114  // Wait for low pass filters to stabilize
115  ROS_INFO_STREAM_NAMED(LOGNAME, "Waiting for low-pass filters to stabilize.");
117 
118  ros::Rate main_rate(1. / ros_parameters_.publish_period);
119 
120  while (ros::ok())
121  {
122  ros::spinOnce();
123 
124  shared_variables_.lock();
125  trajectory_msgs::JointTrajectory outgoing_command = shared_variables_.outgoing_command;
126 
127  // Check for stale cmds
130 
131  // Publish the most recent trajectory, unless the jogging calculation thread tells not to
133  {
134  // Put the outgoing msg in the right format
135  // (trajectory_msgs/JointTrajectory or std_msgs/Float64MultiArray).
136  if (ros_parameters_.command_out_type == "trajectory_msgs/JointTrajectory")
137  {
138  outgoing_command.header.stamp = ros::Time::now();
139  outgoing_cmd_pub.publish(outgoing_command);
140  }
141  else if (ros_parameters_.command_out_type == "std_msgs/Float64MultiArray")
142  {
143  std_msgs::Float64MultiArray joints;
145  joints.data = outgoing_command.points[0].positions;
147  joints.data = outgoing_command.points[0].velocities;
148  outgoing_cmd_pub.publish(joints);
149  }
150  }
152  {
153  ROS_WARN_STREAM_THROTTLE_NAMED(10, LOGNAME, "Stale command. "
154  "Try a larger 'incoming_command_timeout' parameter?");
155  }
156  else
157  {
158  ROS_DEBUG_STREAM_THROTTLE_NAMED(10, LOGNAME, "All-zero command. Doing nothing.");
159  }
160 
161  shared_variables_.unlock();
162 
163  main_rate.sleep();
164  }
165 
166  // Stop JogArm threads
170 }
171 
172 // Listen to cartesian delta commands. Store them in a shared variable.
173 void JogROSInterface::deltaCartesianCmdCB(const geometry_msgs::TwistStampedConstPtr& msg)
174 {
175  shared_variables_.lock();
176 
177  // Copy everything but the frame name. The frame name is set by yaml file at startup.
178  // (so it isn't copied over and over)
179  shared_variables_.command_deltas.twist = msg->twist;
180  shared_variables_.command_deltas.header = msg->header;
181 
182  // Input frame determined by YAML file if not passed with message
183  if (shared_variables_.command_deltas.header.frame_id.empty())
184  {
186  }
187 
188  // Check if input is all zeros. Flag it if so to skip calculations/publication after num_outgoing_halt_msgs_to_publish
190  shared_variables_.command_deltas.twist.linear.y != 0.0 ||
191  shared_variables_.command_deltas.twist.linear.z != 0.0 ||
192  shared_variables_.command_deltas.twist.angular.x != 0.0 ||
193  shared_variables_.command_deltas.twist.angular.y != 0.0 ||
194  shared_variables_.command_deltas.twist.angular.z != 0.0;
195 
197  {
198  shared_variables_.latest_nonzero_cmd_stamp = msg->header.stamp;
199  }
200  shared_variables_.unlock();
201 }
202 
203 // Listen to joint delta commands. Store them in a shared variable.
204 void JogROSInterface::deltaJointCmdCB(const control_msgs::JointJogConstPtr& msg)
205 {
206  shared_variables_.lock();
208 
209  // Check if joint inputs is all zeros. Flag it if so to skip calculations/publication
210  bool all_zeros = true;
211  for (double delta : shared_variables_.joint_command_deltas.velocities)
212  {
213  all_zeros &= (delta == 0.0);
214  };
216 
218  {
219  shared_variables_.latest_nonzero_cmd_stamp = msg->header.stamp;
220  }
221  shared_variables_.unlock();
222 }
223 } // namespace moveit_jog_arm
std::atomic< bool > stop_requested
Definition: jog_arm_data.h:103
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
#define ROS_ERROR_STREAM_NAMED(name, args)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static const std::string LOGNAME
ROSCPP_DECL const std::string & getName()
#define ROS_INFO_STREAM_NAMED(name, args)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
void deltaCartesianCmdCB(const geometry_msgs::TwistStampedConstPtr &msg)
bool startCollisionCheckThread()
Start collision checking.
#define ROS_DEBUG_NAMED(name,...)
trajectory_msgs::JointTrajectory outgoing_command
Definition: jog_arm_data.h:81
geometry_msgs::TwistStamped command_deltas
Definition: jog_arm_data.h:63
void publish(const boost::shared_ptr< M > &message) const
void deltaJointCmdCB(const control_msgs::JointJogConstPtr &msg)
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request &req, moveit_msgs::ChangeDriftDimensions::Response &res)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool stopCollisionCheckThread()
Stop collision checking.
bool stopJogCalcThread()
Stop the main calculation thread.
control_msgs::JointJog joint_command_deltas
Definition: jog_arm_data.h:65
bool sleep()
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request &req, moveit_msgs::ChangeControlDimensions::Response &res)
Start the main calculation thread.
const std::string & getNamespace() const
static Time now()
bool readParameters(ros::NodeHandle &n)
void jointsCB(const sensor_msgs::JointStateConstPtr &msg)
Update the joints of the robot.
bool sleep() const
#define ROS_DEBUG_STREAM_THROTTLE_NAMED(period, name, args)
ROSCPP_DECL void spinOnce()


moveit_jog_arm
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Alexander Rössler
autogenerated on Fri Jun 5 2020 03:53:46