moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
command.hpp
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 : command.hpp
35 * Project : moveit_servo
36 * Created : 06/04/2023
37 * Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim
38 *
39 * Description : The methods that compute the required change in joint angles for various input types.
40 */
41
42#pragma once
43
47#include <rclcpp/rclcpp.hpp>
48#include <tf2_eigen/tf2_eigen.hpp>
49
50namespace moveit_servo
51{
52
61JointDeltaResult jointDeltaFromJointJog(const JointJogCommand& command, const moveit::core::RobotStatePtr& robot_state,
62 const servo::Params& servo_params,
63 const JointNameToMoveGroupIndexMap& joint_name_group_index_map);
64
74JointDeltaResult jointDeltaFromTwist(const TwistCommand& command, const moveit::core::RobotStatePtr& robot_state,
75 const servo::Params& servo_params, const std::string& planning_frame,
76 const JointNameToMoveGroupIndexMap& joint_name_group_index_map);
77
88JointDeltaResult jointDeltaFromPose(const PoseCommand& command, const moveit::core::RobotStatePtr& robot_state,
89 const servo::Params& servo_params, const std::string& planning_frame,
90 const std::string& ee_frame,
91 const JointNameToMoveGroupIndexMap& joint_name_group_index_map);
92
101JointDeltaResult jointDeltaFromIK(const Eigen::VectorXd& cartesian_position_delta,
102 const moveit::core::RobotStatePtr& robot_state, const servo::Params& servo_params,
103 const JointNameToMoveGroupIndexMap& joint_name_group_index_map);
104
105} // namespace moveit_servo
JointDeltaResult jointDeltaFromTwist(const TwistCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const std::string &planning_frame, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given twist command.
Definition command.cpp:147
JointDeltaResult jointDeltaFromJointJog(const JointJogCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given joint jog command.
Definition command.cpp:82
JointDeltaResult jointDeltaFromIK(const Eigen::VectorXd &cartesian_position_delta, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Computes the required change in joint angles for given Cartesian change, using the robot's IK solver.
Definition command.cpp:261
std::pair< StatusCode, Eigen::VectorXd > JointDeltaResult
Definition datatypes.hpp:85
JointDeltaResult jointDeltaFromPose(const PoseCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const std::string &planning_frame, const std::string &ee_frame, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given pose command.
Definition command.cpp:211
std::unordered_map< std::string, std::size_t > JointNameToMoveGroupIndexMap