moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Public Attributes | List of all members
moveit_servo::KinematicState Struct Reference

#include <datatypes.hpp>

Public Member Functions

 KinematicState (const int num_joints)
 
 KinematicState ()
 

Public Attributes

std::vector< std::string > joint_names
 
Eigen::VectorXd positions
 
Eigen::VectorXd velocities
 
Eigen::VectorXd accelerations
 
rclcpp::Time time_stamp
 

Detailed Description

Definition at line 114 of file datatypes.hpp.

Constructor & Destructor Documentation

◆ KinematicState() [1/2]

moveit_servo::KinematicState::KinematicState ( const int  num_joints)
inline

Definition at line 120 of file datatypes.hpp.

◆ KinematicState() [2/2]

moveit_servo::KinematicState::KinematicState ( )
inline

Definition at line 128 of file datatypes.hpp.

Member Data Documentation

◆ accelerations

Eigen::VectorXd moveit_servo::KinematicState::accelerations

Definition at line 117 of file datatypes.hpp.

◆ joint_names

std::vector<std::string> moveit_servo::KinematicState::joint_names

Definition at line 116 of file datatypes.hpp.

◆ positions

Eigen::VectorXd moveit_servo::KinematicState::positions

Definition at line 117 of file datatypes.hpp.

◆ time_stamp

rclcpp::Time moveit_servo::KinematicState::time_stamp

Definition at line 118 of file datatypes.hpp.

◆ velocities

Eigen::VectorXd moveit_servo::KinematicState::velocities

Definition at line 117 of file datatypes.hpp.


The documentation for this struct was generated from the following file: