jog_cpp_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_cpp_interface.cpp
35  * Project : moveit_jog_arm
36  * Created : 11/20/2019
37  * Author : Andy Zelenak
38  */
39 
41 
42 static const std::string LOGNAME = "jog_cpp_interface";
43 
44 namespace moveit_jog_arm
45 {
46 JogCppInterface::JogCppInterface(const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor)
47 {
48  planning_scene_monitor_ = planning_scene_monitor;
49 
50  // Read ROS parameters, typically from YAML file
51  if (!readParameters(nh_))
52  exit(EXIT_FAILURE);
53 }
54 
56 {
57  stopMainLoop();
58 }
59 
61 {
62  // Reset loop termination flag
64  shared_variables_.paused = false;
65 
66  // Crunch the numbers in this thread
68 
69  // Check collisions in this thread
72 
73  // ROS subscriptions. Share the data with the worker threads
74  ros::Subscriber joints_sub =
75  nh_.subscribe(ros_parameters_.joint_topic, 1, &JogInterfaceBase::jointsCB, dynamic_cast<JogInterfaceBase*>(this));
76 
77  // Publish freshly-calculated joints to the robot.
78  // Put the outgoing msg in the right format (trajectory_msgs/JointTrajectory or std_msgs/Float64MultiArray).
79  ros::Publisher outgoing_cmd_pub;
80  if (ros_parameters_.command_out_type == "trajectory_msgs/JointTrajectory")
81  outgoing_cmd_pub = nh_.advertise<trajectory_msgs::JointTrajectory>(ros_parameters_.command_out_topic, 1);
82  else if (ros_parameters_.command_out_type == "std_msgs/Float64MultiArray")
83  outgoing_cmd_pub = nh_.advertise<std_msgs::Float64MultiArray>(ros_parameters_.command_out_topic, 1);
84 
85  // Wait for incoming topics to appear
86  ROS_DEBUG_NAMED(LOGNAME, "Waiting for JointState topic");
87  ros::topic::waitForMessage<sensor_msgs::JointState>(ros_parameters_.joint_topic);
88 
89  // Wait for low pass filters to stabilize
90  ROS_INFO_STREAM_NAMED(LOGNAME, "Waiting for low-pass filters to stabilize.");
92 
94 
96  {
97  ros::spinOnce();
98 
100  {
101  shared_variables_.lock();
102  trajectory_msgs::JointTrajectory outgoing_command = shared_variables_.outgoing_command;
103 
104  // Check if incoming commands are stale
107 
108  // Publish the most recent trajectory, unless the jogging calculation thread tells not to
110  {
111  // Put the outgoing msg in the right format
112  // (trajectory_msgs/JointTrajectory or std_msgs/Float64MultiArray).
113  if (ros_parameters_.command_out_type == "trajectory_msgs/JointTrajectory")
114  {
115  outgoing_command.header.stamp = ros::Time::now();
116  outgoing_cmd_pub.publish(outgoing_command);
117  }
118  else if (ros_parameters_.command_out_type == "std_msgs/Float64MultiArray")
119  {
120  std_msgs::Float64MultiArray joints;
122  joints.data = outgoing_command.points[0].positions;
124  joints.data = outgoing_command.points[0].velocities;
125  outgoing_cmd_pub.publish(joints);
126  }
127  }
129  {
130  ROS_WARN_STREAM_THROTTLE_NAMED(10, LOGNAME, "Stale command. "
131  "Try a larger 'incoming_command_timeout' parameter?");
132  }
133  else
134  {
135  ROS_DEBUG_STREAM_THROTTLE_NAMED(10, LOGNAME, "All-zero command. Doing nothing.");
136  }
137 
138  shared_variables_.unlock();
139  }
140 
141  main_rate.sleep();
142  }
143 
146 }
147 
149 {
151 }
152 
153 void JogCppInterface::setPaused(bool paused)
154 {
155  shared_variables_.paused = paused;
156 }
157 
158 void JogCppInterface::provideTwistStampedCommand(const geometry_msgs::TwistStamped& velocity_command)
159 {
160  shared_variables_.lock();
161 
162  shared_variables_.command_deltas.twist = velocity_command.twist;
163  shared_variables_.command_deltas.header = velocity_command.header;
164 
165  // Input frame determined by YAML file if not passed with message
166  if (shared_variables_.command_deltas.header.frame_id.empty())
167  {
169  }
170 
171  // Check if input is all zeros. Flag it if so to skip calculations/publication after num_outgoing_halt_msgs_to_publish
173  shared_variables_.command_deltas.twist.linear.y != 0.0 ||
174  shared_variables_.command_deltas.twist.linear.z != 0.0 ||
175  shared_variables_.command_deltas.twist.angular.x != 0.0 ||
176  shared_variables_.command_deltas.twist.angular.y != 0.0 ||
177  shared_variables_.command_deltas.twist.angular.z != 0.0;
178 
180  {
181  shared_variables_.latest_nonzero_cmd_stamp = velocity_command.header.stamp;
182  }
183  shared_variables_.unlock();
184 };
185 
186 void JogCppInterface::provideJointCommand(const control_msgs::JointJog& joint_command)
187 {
188  shared_variables_.lock();
189  shared_variables_.joint_command_deltas = joint_command;
190 
191  // Check if joint inputs is all zeros. Flag it if so to skip calculations/publication
192  bool all_zeros = true;
193  for (double delta : shared_variables_.joint_command_deltas.velocities)
194  {
195  all_zeros &= (delta == 0.0);
196  };
198 
200  {
201  shared_variables_.latest_nonzero_cmd_stamp = joint_command.header.stamp;
202  }
203  shared_variables_.unlock();
204 }
205 
206 sensor_msgs::JointState JogCppInterface::getJointState()
207 {
208  shared_variables_.lock();
209  sensor_msgs::JointState current_joints = shared_variables_.joints;
210  shared_variables_.unlock();
211 
212  return current_joints;
213 }
214 
215 bool JogCppInterface::getCommandFrameTransform(Eigen::Isometry3d& transform)
216 {
217  if (!jog_calcs_ || !jog_calcs_->isInitialized())
218  return false;
219 
220  shared_variables_.lock();
222  shared_variables_.unlock();
223 
224  // All zeros means the transform wasn't initialized, so return false
225  return !transform.matrix().isZero(0);
226 }
227 
229 {
230  return shared_variables_.status;
231 }
232 } // namespace moveit_jog_arm
std::atomic< bool > stop_requested
Definition: jog_arm_data.h:103
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::atomic< bool > paused
Definition: jog_arm_data.h:100
Eigen::Isometry3d tf_moveit_to_cmd_frame
Definition: jog_arm_data.h:90
#define ROS_INFO_STREAM_NAMED(name, args)
static const std::string LOGNAME
sensor_msgs::JointState joints
Definition: jog_arm_data.h:67
bool startCollisionCheckThread()
Start collision checking.
void provideJointCommand(const control_msgs::JointJog &joint_command)
Send joint position(s) commands.
#define ROS_DEBUG_NAMED(name,...)
void setPaused(bool paused)
Pause or unpause processing jog commands while keeping the main loop alive.
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
std::unique_ptr< JogCalcs > jog_calcs_
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
ROSCPP_DECL bool ok()
void provideTwistStampedCommand(const geometry_msgs::TwistStamped &velocity_command)
Provide a Cartesian velocity command to the jogger. The units are determined by settings in the yaml ...
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()
JogCppInterface(const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
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()
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
sensor_msgs::JointState getJointState()
std::atomic< StatusCode > status
Definition: jog_arm_data.h:97


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