cartesian_state.h
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2021 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 #pragma once
19 
20 // Eigen
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"
26 
27 #include <cartesian_control_msgs/CartesianTrajectoryPoint.h>
28 
30 {
39 {
44 
52  CartesianState(const cartesian_control_msgs::CartesianTrajectoryPoint& point);
53 
64  CartesianState operator-(const CartesianState& other) const;
65 
73  cartesian_control_msgs::CartesianTrajectoryPoint toMsg(int time_from_start = 0) const;
74 
80  Eigen::Vector3d rot() const
81  {
82  Eigen::AngleAxisd a(q);
83  return a.axis() * a.angle();
84  };
85 
94  friend std::ostream& operator<<(std::ostream& os, const CartesianState& state);
95 
96  // Pose
97  Eigen::Vector3d p;
98  Eigen::Quaterniond q;
99 
100  // Spatial velocity in body (waypoint) coordinates
101  Eigen::Vector3d v;
102  Eigen::Vector3d w;
103 
104  // Spatial acceleration in body (waypoint) coordinates
105  Eigen::Vector3d v_dot;
106  Eigen::Vector3d w_dot;
107 };
108 
109 } // namespace ros_controllers_cartesian
ros_controllers_cartesian
Definition: cartesian_state.h:29
ros_controllers_cartesian::CartesianState::v
Eigen::Vector3d v
linear velocity,
Definition: cartesian_state.h:101
ros_controllers_cartesian::CartesianState::operator<<
friend std::ostream & operator<<(std::ostream &os, const CartesianState &state)
Stream operator for testing and debugging.
Definition: cartesian_state.cpp:113
ros_controllers_cartesian::CartesianState::v_dot
Eigen::Vector3d v_dot
linear acceleration,
Definition: cartesian_state.h:105
ros_controllers_cartesian::CartesianState::q
Eigen::Quaterniond q
rotation
Definition: cartesian_state.h:98
ros_controllers_cartesian::CartesianState::w_dot
Eigen::Vector3d w_dot
angular acceleration,
Definition: cartesian_state.h:106
ros_controllers_cartesian::CartesianState::operator-
CartesianState operator-(const CartesianState &other) const
Difference operator between states.
Definition: cartesian_state.cpp:81
ros_controllers_cartesian::CartesianState::rot
Eigen::Vector3d rot() const
Get Euler-Rodrigues vector from orientation.
Definition: cartesian_state.h:80
ros_controllers_cartesian::CartesianState
Cartesian state with pose, velocity and acceleration.
Definition: cartesian_state.h:38
ros_controllers_cartesian::CartesianState::CartesianState
CartesianState()
Initializes all quantities to zero and sets the orientation quaternion to identity.
Definition: cartesian_state.cpp:46
ros_controllers_cartesian::CartesianState::p
Eigen::Vector3d p
position
Definition: cartesian_state.h:97
ros_controllers_cartesian::CartesianState::w
Eigen::Vector3d w
angular velocity,
Definition: cartesian_state.h:102
ros_controllers_cartesian::CartesianState::toMsg
cartesian_control_msgs::CartesianTrajectoryPoint toMsg(int time_from_start=0) const
Convenience method for conversion.
Definition: cartesian_state.cpp:94


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