Go to the documentation of this file.
21 #include <Eigen/Dense>
22 #include <Eigen/Geometry>
23 #include "Eigen/src/Core/Matrix.h"
24 #include "Eigen/src/Geometry/AngleAxis.h"
25 #include "Eigen/src/Geometry/Quaternion.h"
27 #include <cartesian_control_msgs/CartesianTrajectoryPoint.h>
52 CartesianState(
const cartesian_control_msgs::CartesianTrajectoryPoint& point);
73 cartesian_control_msgs::CartesianTrajectoryPoint
toMsg(
int time_from_start = 0)
const;
80 Eigen::Vector3d
rot()
const
82 Eigen::AngleAxisd a(
q);
83 return a.axis() * a.angle();
Eigen::Vector3d v
linear velocity,
friend std::ostream & operator<<(std::ostream &os, const CartesianState &state)
Stream operator for testing and debugging.
Eigen::Vector3d v_dot
linear acceleration,
Eigen::Quaterniond q
rotation
Eigen::Vector3d w_dot
angular acceleration,
CartesianState operator-(const CartesianState &other) const
Difference operator between states.
Eigen::Vector3d rot() const
Get Euler-Rodrigues vector from orientation.
Cartesian state with pose, velocity and acceleration.
CartesianState()
Initializes all quantities to zero and sets the orientation quaternion to identity.
Eigen::Vector3d p
position
Eigen::Vector3d w
angular velocity,
cartesian_control_msgs::CartesianTrajectoryPoint toMsg(int time_from_start=0) const
Convenience method for conversion.