jog_arm_data.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : jog_arm_data.h
3  * Project : moveit_jog_arm
4  * Created : 1/11/2019
5  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
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 #pragma once
40 
41 // System
42 #include <mutex>
43 #include <thread>
44 
45 // Eigen
46 #include <Eigen/Geometry>
47 
48 // ROS
49 #include <control_msgs/JointJog.h>
50 #include <geometry_msgs/TwistStamped.h>
51 #include <sensor_msgs/JointState.h>
52 #include <trajectory_msgs/JointTrajectory.h>
53 
54 // moveit_jog_arm
55 #include "status_codes.h"
56 
57 namespace moveit_jog_arm
58 {
59 // Variables to share between threads, and their mutexes
60 // Inherit from a mutex so the struct can be locked/unlocked easily
61 struct JogArmShared : public std::mutex
62 {
63  geometry_msgs::TwistStamped command_deltas;
64 
65  control_msgs::JointJog joint_command_deltas;
66 
67  sensor_msgs::JointState joints;
68 
70 
71  // Flag a valid incoming Cartesian command having nonzero velocities
73 
74  // Flag a valid incoming joint angle command having nonzero velocities
75  bool have_nonzero_joint_cmd = false;
76 
77  // Indicates that we have not received a new command in some time
78  bool command_is_stale = false;
79 
80  // The new command which is calculated
81  trajectory_msgs::JointTrajectory outgoing_command;
82 
83  // Timestamp of incoming commands
85 
86  // Indicates no collision, etc, so outgoing commands can be sent
87  bool ok_to_publish = false;
88 
89  // The transform from the MoveIt planning frame to robot_link_command_frame
90  Eigen::Isometry3d tf_moveit_to_cmd_frame;
91 
92  // True -> allow drift in this dimension. In the command frame. [x, y, z, roll, pitch, yaw]
93  std::atomic_bool drift_dimensions[6] = { ATOMIC_VAR_INIT(false), ATOMIC_VAR_INIT(false), ATOMIC_VAR_INIT(false),
94  ATOMIC_VAR_INIT(false), ATOMIC_VAR_INIT(false), ATOMIC_VAR_INIT(false) };
95 
96  // Status of the jogger. 0 for no warning. The meaning of nonzero values can be seen in status_codes.h
97  std::atomic<StatusCode> status;
98 
99  // Pause/unpause jog threads - threads are not paused by default
100  std::atomic<bool> paused{ false };
101 
102  // Stop jog loop threads - threads are not stopped by default
103  std::atomic<bool> stop_requested{ false };
104 
105  // The dimesions to control. In the command frame. [x, y, z, roll, pitch, yaw]
106  std::atomic_bool control_dimensions[6] = { ATOMIC_VAR_INIT(true), ATOMIC_VAR_INIT(true), ATOMIC_VAR_INIT(true),
107  ATOMIC_VAR_INIT(true), ATOMIC_VAR_INIT(true), ATOMIC_VAR_INIT(true) };
108 };
109 
110 // ROS params to be read. See the yaml file in /config for a description of each.
112 {
113  std::string move_group_name;
114  std::string joint_topic;
117  std::string command_out_topic;
118  std::string planning_frame;
119  std::string status_topic;
121  std::string command_in_type;
122  std::string command_out_type;
123  double linear_scale;
125  double joint_scale;
141 };
142 } // namespace moveit_jog_arm
std::atomic< bool > stop_requested
Definition: jog_arm_data.h:103
std::atomic< bool > paused
Definition: jog_arm_data.h:100
Eigen::Isometry3d tf_moveit_to_cmd_frame
Definition: jog_arm_data.h:90
sensor_msgs::JointState joints
Definition: jog_arm_data.h:67
std::atomic_bool drift_dimensions[6]
Definition: jog_arm_data.h:93
trajectory_msgs::JointTrajectory outgoing_command
Definition: jog_arm_data.h:81
geometry_msgs::TwistStamped command_deltas
Definition: jog_arm_data.h:63
std::atomic_bool control_dimensions[6]
Definition: jog_arm_data.h:106
control_msgs::JointJog joint_command_deltas
Definition: jog_arm_data.h:65
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