39 #include <pybind11/pybind11.h>
40 #include <pybind11/stl.h>
41 #include <pybind11/eigen.h>
43 #include <tf2_eigen/tf2_eigen.hpp>
50 namespace bind_robot_state
62 const std::string& joint_model_group_name);
64 const std::string& joint_model_group_name);
67 const std::string& link_model_name,
const Eigen::Vector3d& reference_point_position,
68 bool use_quaternion_representation);
74 const std::string& state_name);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Vec3fX< details::Vec3Data< double > > Vector3d
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)