servo_parameters.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : servo_parameters.h
3  * Project : moveit_servo
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 namespace moveit_servo
42 {
43 // Size of queues used in ros pub/sub/service
44 constexpr size_t ROS_QUEUE_SIZE = 2;
45 
46 // ROS params to be read. See the yaml file in /config for a description of each.
47 struct ServoParameters
48 {
49  std::string move_group_name;
50  std::string joint_topic;
51  std::string cartesian_command_in_topic;
52  std::string robot_link_command_frame;
53  std::string command_out_topic;
54  std::string planning_frame;
55  std::string ee_frame_name;
56  std::string status_topic;
57  std::string joint_command_in_topic;
58  std::string command_in_type;
59  std::string command_out_type;
60  double linear_scale;
61  double rotational_scale;
62  double joint_scale;
65  double low_pass_filter_coeff;
66  double publish_period;
68  double joint_limit_margin;
70  bool use_gazebo;
74  bool low_latency_mode;
75  // Collision checking
76  bool check_collisions;
77  std::string collision_check_type;
78  double collision_check_rate;
83 };
84 
85 } // namespace moveit_servo
moveit_servo::ServoParameters::use_gazebo
bool use_gazebo
Definition: servo_parameters.h:106
moveit_servo::ROS_QUEUE_SIZE
constexpr size_t ROS_QUEUE_SIZE
Definition: servo_parameters.h:80
moveit_servo::ServoParameters::incoming_command_timeout
double incoming_command_timeout
Definition: servo_parameters.h:103
moveit_servo::ServoParameters::linear_scale
double linear_scale
Definition: servo_parameters.h:96
moveit_servo::ServoParameters::self_collision_proximity_threshold
double self_collision_proximity_threshold
Definition: servo_parameters.h:116
moveit_servo::ServoParameters::joint_command_in_topic
std::string joint_command_in_topic
Definition: servo_parameters.h:93
moveit_servo::ServoParameters::num_outgoing_halt_msgs_to_publish
int num_outgoing_halt_msgs_to_publish
Definition: servo_parameters.h:105
moveit_servo::ServoParameters::move_group_name
std::string move_group_name
Definition: servo_parameters.h:85
moveit_servo::ServoParameters::command_out_type
std::string command_out_type
Definition: servo_parameters.h:95
moveit_servo::ServoParameters::status_topic
std::string status_topic
Definition: servo_parameters.h:92
moveit_servo::ServoParameters::planning_frame
std::string planning_frame
Definition: servo_parameters.h:90
moveit_servo::ServoParameters::joint_scale
double joint_scale
Definition: servo_parameters.h:98
moveit_servo::ServoParameters::collision_check_type
std::string collision_check_type
Definition: servo_parameters.h:113
moveit_servo::ServoParameters::joint_limit_margin
double joint_limit_margin
Definition: servo_parameters.h:104
moveit_servo::ServoParameters::rotational_scale
double rotational_scale
Definition: servo_parameters.h:97
moveit_servo::ServoParameters::ee_frame_name
std::string ee_frame_name
Definition: servo_parameters.h:91
moveit_servo
Definition: collision_check.h:50
moveit_servo::ServoParameters::low_latency_mode
bool low_latency_mode
Definition: servo_parameters.h:110
moveit_servo::ServoParameters::cartesian_command_in_topic
std::string cartesian_command_in_topic
Definition: servo_parameters.h:87
moveit_servo::ServoParameters::scene_collision_proximity_threshold
double scene_collision_proximity_threshold
Definition: servo_parameters.h:115
moveit_servo::ServoParameters::collision_check_rate
double collision_check_rate
Definition: servo_parameters.h:114
moveit_servo::ServoParameters::lower_singularity_threshold
double lower_singularity_threshold
Definition: servo_parameters.h:99
moveit_servo::ServoParameters::min_allowable_collision_distance
double min_allowable_collision_distance
Definition: servo_parameters.h:118
moveit_servo::ServoParameters::hard_stop_singularity_threshold
double hard_stop_singularity_threshold
Definition: servo_parameters.h:100
moveit_servo::ServoParameters::collision_distance_safety_factor
double collision_distance_safety_factor
Definition: servo_parameters.h:117
moveit_servo::ServoParameters::publish_joint_positions
bool publish_joint_positions
Definition: servo_parameters.h:107
moveit_servo::ServoParameters::robot_link_command_frame
std::string robot_link_command_frame
Definition: servo_parameters.h:88
moveit_servo::ServoParameters::joint_topic
std::string joint_topic
Definition: servo_parameters.h:86
moveit_servo::ServoParameters::publish_period
double publish_period
Definition: servo_parameters.h:102
moveit_servo::ServoParameters::command_in_type
std::string command_in_type
Definition: servo_parameters.h:94
moveit_servo::ServoParameters::command_out_topic
std::string command_out_topic
Definition: servo_parameters.h:89
moveit_servo::ServoParameters::check_collisions
bool check_collisions
Definition: servo_parameters.h:112
moveit_servo::ServoParameters::publish_joint_velocities
bool publish_joint_velocities
Definition: servo_parameters.h:108
moveit_servo::ServoParameters::low_pass_filter_coeff
double low_pass_filter_coeff
Definition: servo_parameters.h:101
moveit_servo::ServoParameters::publish_joint_accelerations
bool publish_joint_accelerations
Definition: servo_parameters.h:109


moveit_servo
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Alexander Rössler , Tyler Weaver
autogenerated on Sat May 3 2025 02:27:56