jog_interface_base.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : jog_interface_base.cpp
3  * Project : moveit_jog_arm
4  * Created : 3/9/2017
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 #include "collision_check_thread.h"
40 #include <Eigen/Eigenvalues>
41 #include "jog_arm_data.h"
42 #include "jog_calcs.h"
43 #include "low_pass_filter.h"
45 #include <moveit_msgs/ChangeDriftDimensions.h>
46 #include <moveit_msgs/ChangeControlDimensions.h>
48 #include <sensor_msgs/Joy.h>
49 #include <std_msgs/Float64MultiArray.h>
50 
51 namespace moveit_jog_arm
52 {
58 {
59 public:
61 
63  void jointsCB(const sensor_msgs::JointStateConstPtr& msg);
64 
73  bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request& req,
74  moveit_msgs::ChangeDriftDimensions::Response& res);
75 
77  // Service callback for changing jogging dimensions
78  bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request& req,
79  moveit_msgs::ChangeControlDimensions::Response& res);
80 
81  // Jogging calculation thread
82  bool startJogCalcThread();
83 
85  bool stopJogCalcThread();
86 
89 
92 
93 protected:
95 
96  // Pointer to the collision environment
97  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
98 
99  // Store the parameters that were read from ROS server
101 
102  // Share data between threads
104 
105  // Jog calcs
106  std::unique_ptr<JogCalcs> jog_calcs_;
107  std::unique_ptr<std::thread> jog_calc_thread_;
108 
109  // Collision checks
110  std::unique_ptr<CollisionCheckThread> collision_checker_;
111  std::unique_ptr<std::thread> collision_check_thread_;
112 };
113 } // namespace moveit_jog_arm
std::unique_ptr< CollisionCheckThread > collision_checker_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
bool startCollisionCheckThread()
Start collision checking.
std::unique_ptr< std::thread > jog_calc_thread_
std::unique_ptr< std::thread > collision_check_thread_
std::unique_ptr< JogCalcs > jog_calcs_
bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request &req, moveit_msgs::ChangeDriftDimensions::Response &res)
bool stopCollisionCheckThread()
Stop collision checking.
bool stopJogCalcThread()
Stop the main calculation thread.
res
bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request &req, moveit_msgs::ChangeControlDimensions::Response &res)
Start the main calculation thread.
bool readParameters(ros::NodeHandle &n)
void jointsCB(const sensor_msgs::JointStateConstPtr &msg)
Update the joints of the robot.


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