include
moveit_jog_arm
collision_check_thread.h
Go to the documentation of this file.
1
/*******************************************************************************
2
* Title : collision_check_thread.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
#include <atomic>
42
#include "
jog_arm_data.h
"
43
#include "
low_pass_filter.h
"
44
#include <
moveit/robot_model_loader/robot_model_loader.h
>
45
#include <
moveit/planning_scene_monitor/planning_scene_monitor.h
>
46
47
namespace
moveit_jog_arm
48
{
49
class
CollisionCheckThread
50
{
51
public
:
57
CollisionCheckThread
(
const
moveit_jog_arm::JogArmParameters
& parameters,
58
const
planning_scene_monitor::PlanningSceneMonitorPtr&
planning_scene_monitor
);
59
60
// Get thread-safe read-only lock of planning scene
61
planning_scene_monitor::LockedPlanningSceneRO
getLockedPlanningSceneRO
()
const
;
62
63
void
startMainLoop
(
moveit_jog_arm::JogArmShared
& shared_variables);
64
65
private
:
66
const
moveit_jog_arm::JogArmParameters
parameters_
;
67
68
// Pointer to the collision environment
69
planning_scene_monitor::PlanningSceneMonitorPtr
planning_scene_monitor_
;
70
};
71
}
// namespace moveit_jog_arm
moveit_jog_arm::CollisionCheckThread::startMainLoop
void startMainLoop(moveit_jog_arm::JogArmShared &shared_variables)
Definition:
collision_check_thread.cpp:62
planning_scene_monitor
moveit_jog_arm::CollisionCheckThread::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition:
collision_check_thread.h:69
planning_scene_monitor.h
low_pass_filter.h
moveit_jog_arm::JogArmParameters
Definition:
jog_arm_data.h:111
jog_arm_data.h
moveit_jog_arm::CollisionCheckThread::parameters_
const moveit_jog_arm::JogArmParameters parameters_
Definition:
collision_check_thread.h:66
moveit_jog_arm::CollisionCheckThread
Definition:
collision_check_thread.h:49
moveit_jog_arm::CollisionCheckThread::CollisionCheckThread
CollisionCheckThread(const moveit_jog_arm::JogArmParameters ¶meters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Constructor.
Definition:
collision_check_thread.cpp:48
moveit_jog_arm::JogArmShared
Definition:
jog_arm_data.h:61
moveit_jog_arm
Definition:
collision_check_thread.h:47
moveit_jog_arm::CollisionCheckThread::getLockedPlanningSceneRO
planning_scene_monitor::LockedPlanningSceneRO getLockedPlanningSceneRO() const
Definition:
collision_check_thread.cpp:57
planning_scene_monitor::LockedPlanningSceneRO
robot_model_loader.h
moveit_jog_arm
Author(s): Brian O'Neil, Andy Zelenak
, Blake Anderson, Alexander Rössler
autogenerated on Fri Jun 5 2020 03:53:46