moveit2
The MoveIt Motion Planning Framework for ROS 2.
servo.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 : servo.cpp
35  * Project : moveit_servo
36  * Created : 3/9/2017
37  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
38  */
39 
41 #include <moveit_servo/servo.h>
42 
43 namespace moveit_servo
44 {
45 namespace
46 {
47 const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.servo");
48 constexpr double ROBOT_STATE_WAIT_TIME = 10.0; // seconds
49 } // namespace
50 
51 Servo::Servo(const rclcpp::Node::SharedPtr& node, const ServoParameters::SharedConstPtr& parameters,
52  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor)
53  : planning_scene_monitor_{ planning_scene_monitor }
54  , parameters_{ parameters }
55  , servo_calcs_{ node, parameters, planning_scene_monitor_ }
56  , collision_checker_{ node, parameters, planning_scene_monitor_ }
57 {
58 }
59 
61 {
62  if (!planning_scene_monitor_->getStateMonitor()->waitForCompleteState(parameters_->move_group_name,
63  ROBOT_STATE_WAIT_TIME))
64  {
65  RCLCPP_ERROR(LOGGER, "Timeout waiting for current state");
66  return;
67  }
68 
69  setPaused(false);
70 
71  // Crunch the numbers in this timer
72  servo_calcs_.start();
73 
74  // Check collisions in this timer
75  if (parameters_->check_collisions)
76  collision_checker_.start();
77 }
78 
80 {
81  setPaused(true);
82 }
83 
84 void Servo::setPaused(bool paused)
85 {
86  servo_calcs_.setPaused(paused);
87  collision_checker_.setPaused(paused);
88 }
89 
90 bool Servo::getCommandFrameTransform(Eigen::Isometry3d& transform)
91 {
92  return servo_calcs_.getCommandFrameTransform(transform);
93 }
94 
95 bool Servo::getCommandFrameTransform(geometry_msgs::msg::TransformStamped& transform)
96 {
97  return servo_calcs_.getCommandFrameTransform(transform);
98 }
99 
100 bool Servo::getEEFrameTransform(Eigen::Isometry3d& transform)
101 {
102  return servo_calcs_.getEEFrameTransform(transform);
103 }
104 
105 bool Servo::getEEFrameTransform(geometry_msgs::msg::TransformStamped& transform)
106 {
107  return servo_calcs_.getEEFrameTransform(transform);
108 }
109 
111 {
112  return parameters_;
113 }
114 
115 } // namespace moveit_servo
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
void start()
start the Timer that regulates collision check rate
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
bool getEEFrameTransform(Eigen::Isometry3d &transform)
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
void start()
Start the timer where we do work and publish outputs.
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
Definition: servo.cpp:84
const ServoParameters::SharedConstPtr & getParameters() const
Get the parameters used by servo node.
Definition: servo.cpp:110
bool getEEFrameTransform(Eigen::Isometry3d &transform)
Definition: servo.cpp:100
void start()
start servo node
Definition: servo.cpp:60
Servo(const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr &parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Definition: servo.cpp:51
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
Definition: servo.cpp:90
const rclcpp::Logger LOGGER
Definition: async_test.h:31
std::shared_ptr< const ServoParameters > SharedConstPtr