moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
robot_state.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2022, Peter David Fagan
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
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of PickNik Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Peter David Fagan */
36
37#pragma once
38
39#include <pybind11/pybind11.h>
40#include <pybind11/stl.h>
41#pragma GCC diagnostic push
42#if defined(__GNUC__) && !defined(__clang__)
43#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
44#endif
45#include <pybind11/eigen.h>
46#pragma GCC diagnostic pop
48#include <tf2_eigen/tf2_eigen.hpp>
50
51namespace py = pybind11;
52
53namespace moveit_py
54{
55namespace bind_robot_state
56{
57void update(moveit::core::RobotState* self, bool force, std::string& category);
58
59Eigen::MatrixXd getFrameTransform(const moveit::core::RobotState* self, std::string& frame_id);
60
61Eigen::MatrixXd getGlobalLinkTransform(const moveit::core::RobotState* self, std::string& link_name);
62
63geometry_msgs::msg::Pose getPose(const moveit::core::RobotState* self, const std::string& link_name);
64
65Eigen::VectorXd copyJointGroupPositions(const moveit::core::RobotState* self, const std::string& joint_model_group_name);
66Eigen::VectorXd copyJointGroupVelocities(const moveit::core::RobotState* self,
67 const std::string& joint_model_group_name);
69 const std::string& joint_model_group_name);
70
71Eigen::MatrixXd getJacobian(const moveit::core::RobotState* self, const std::string& joint_model_group_name,
72 const std::string& link_model_name, const Eigen::Vector3d& reference_point_position,
73 bool use_quaternion_representation);
74
75Eigen::MatrixXd getJacobian(const moveit::core::RobotState* self, const std::string& joint_model_group_name,
76 const Eigen::Vector3d& reference_point_position);
77
78bool setToDefaultValues(moveit::core::RobotState* self, const std::string& joint_model_group_name,
79 const std::string& state_name);
80
81void initRobotState(py::module& m);
82} // namespace bind_robot_state
83} // namespace moveit_py
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
Eigen::VectorXd copyJointGroupVelocities(const moveit::core::RobotState *self, const std::string &joint_model_group_name)
Eigen::MatrixXd getJacobian(const moveit::core::RobotState *self, const std::string &joint_model_group_name, const Eigen::Vector3d &reference_point_position)
bool setToDefaultValues(moveit::core::RobotState *self, const std::string &joint_model_group_name, const std::string &state_name)
void initRobotState(py::module &m)
Eigen::MatrixXd getGlobalLinkTransform(const moveit::core::RobotState *self, std::string &link_name)
Eigen::VectorXd copyJointGroupAccelerations(const moveit::core::RobotState *self, const std::string &joint_model_group_name)
void update(moveit::core::RobotState *self, bool force, std::string &category)
Eigen::VectorXd copyJointGroupPositions(const moveit::core::RobotState *self, const std::string &joint_model_group_name)
geometry_msgs::msg::Pose getPose(const moveit::core::RobotState *self, const std::string &link_name)
Eigen::MatrixXd getFrameTransform(const moveit::core::RobotState *self, std::string &frame_id)