OpenWalker Project
Documentation of the ROS Packages
|
The CartesianVelocity class. More...
#include <cartesian_velocity.h>
Public Types | |
typedef _Scalar | Scalar |
typedef Eigen::Matrix< Scalar, 6, 1 > | Base |
Public Member Functions | |
CartesianVelocity () | |
Default Constructor. | |
template<typename OtherDerived > | |
CartesianVelocity (const Eigen::EigenBase< OtherDerived > &other) | |
Copy constructor. More... | |
CartesianVelocity (const geometry_msgs::Twist &other) | |
Copy constructor form geometry_msgs::Twist. | |
void | operator= (const geometry_msgs::Twist &Xp) |
Assignment form geometry_msgs::Twist. | |
operator geometry_msgs::Twist () const | |
Conversion to geometry_msgs::Twist. | |
geometry_msgs::Twist | toTwistMsg () const |
Conversion to geometry_msgs::Twist. | |
LinearVelocityRef< Base > | linear () |
access to linear part | |
LinearVelocityRef< const Base > | linear () const |
const access to linear part | |
AngularVelocityRef< Base > | angular () |
access to angular part | |
AngularVelocityRef< const Base > | angular () const |
const access to angular part | |
std::string | toString () const |
Conversion to std::string. | |
Static Public Member Functions | |
static const CartesianVelocity< Scalar > & | Default () |
Construct as Default. More... | |
The CartesianVelocity class.
The CartesianVelocity is of type Eigen::Vector6 and is represented by the math symbol .
Stores the linear and angular velocity in a 6 dimensional vector. The linear velocity part is represented by the first three elements. The angular velocity by the last three elements.
|
inline |
Copy constructor.
This copy constructor not only works with Eigen matrices but also with their expressions.
|
inlinestatic |
Construct as Default.
Default is Identity