Public Member Functions | Public Attributes | Friends | List of all members
ros_controllers_cartesian::CartesianState Struct Reference

Cartesian state with pose, velocity and acceleration. More...

#include <cartesian_state.h>

Public Member Functions

 CartesianState ()
 Initializes all quantities to zero and sets the orientation quaternion to identity. More...
 
 CartesianState (const cartesian_control_msgs::CartesianTrajectoryPoint &point)
 Convenience constructor for ROS messages. More...
 
CartesianState operator- (const CartesianState &other) const
 Difference operator between states. More...
 
Eigen::Vector3d rot () const
 Get Euler-Rodrigues vector from orientation. More...
 
cartesian_control_msgs::CartesianTrajectoryPoint toMsg (int time_from_start=0) const
 Convenience method for conversion. More...
 

Public Attributes

Eigen::Vector3d p
 position More...
 
Eigen::Quaterniond q
 rotation More...
 
Eigen::Vector3d v
 linear velocity, $ v $ More...
 
Eigen::Vector3d v_dot
 linear acceleration, $ \dot{v} $ More...
 
Eigen::Vector3d w
 angular velocity, $ \omega $ More...
 
Eigen::Vector3d w_dot
 angular acceleration, $ \dot{\omega} $ More...
 

Friends

std::ostream & operator<< (std::ostream &os, const CartesianState &state)
 Stream operator for testing and debugging. More...
 

Detailed Description

Cartesian state with pose, velocity and acceleration.

All quantities are assumed to be given in one common reference frame. This frame is also the reference for the pose defined by p and q.

Definition at line 38 of file cartesian_state.h.

Constructor & Destructor Documentation

◆ CartesianState() [1/2]

ros_controllers_cartesian::CartesianState::CartesianState ( )

Initializes all quantities to zero and sets the orientation quaternion to identity.

Definition at line 46 of file cartesian_state.cpp.

◆ CartesianState() [2/2]

ros_controllers_cartesian::CartesianState::CartesianState ( const cartesian_control_msgs::CartesianTrajectoryPoint &  point)

Convenience constructor for ROS messages.

Implicitly normalizes the point's orientation quaternion.

Parameters
pointThe desired state

Definition at line 61 of file cartesian_state.cpp.

Member Function Documentation

◆ operator-()

CartesianState ros_controllers_cartesian::CartesianState::operator- ( const CartesianState other) const

Difference operator between states.

This is the element-wise difference for all vector quantities and the difference of rotation for the quaternion.

Parameters
otherState to subtract
Returns
The element-wise difference of the two.

Definition at line 81 of file cartesian_state.cpp.

◆ rot()

Eigen::Vector3d ros_controllers_cartesian::CartesianState::rot ( ) const
inline

Get Euler-Rodrigues vector from orientation.

Returns
The orientation in axis-angle notation

Definition at line 80 of file cartesian_state.h.

◆ toMsg()

cartesian_control_msgs::CartesianTrajectoryPoint ros_controllers_cartesian::CartesianState::toMsg ( int  time_from_start = 0) const

Convenience method for conversion.

Parameters
time_from_startTime from start in seconds
Returns
Cartesian State in trajectory waypoint representation

Definition at line 94 of file cartesian_state.cpp.

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream &  os,
const CartesianState state 
)
friend

Stream operator for testing and debugging.

Parameters
osThe output stream
stateThe CartesianState
Returns
Reference to the stream for chaining

Definition at line 113 of file cartesian_state.cpp.

Member Data Documentation

◆ p

Eigen::Vector3d ros_controllers_cartesian::CartesianState::p

position

Definition at line 97 of file cartesian_state.h.

◆ q

Eigen::Quaterniond ros_controllers_cartesian::CartesianState::q

rotation

Definition at line 98 of file cartesian_state.h.

◆ v

Eigen::Vector3d ros_controllers_cartesian::CartesianState::v

linear velocity, $ v $

Definition at line 101 of file cartesian_state.h.

◆ v_dot

Eigen::Vector3d ros_controllers_cartesian::CartesianState::v_dot

linear acceleration, $ \dot{v} $

Definition at line 105 of file cartesian_state.h.

◆ w

Eigen::Vector3d ros_controllers_cartesian::CartesianState::w

angular velocity, $ \omega $

Definition at line 102 of file cartesian_state.h.

◆ w_dot

Eigen::Vector3d ros_controllers_cartesian::CartesianState::w_dot

angular acceleration, $ \dot{\omega} $

Definition at line 106 of file cartesian_state.h.


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


cartesian_trajectory_interpolation
Author(s):
autogenerated on Tue Oct 15 2024 02:09:14