cartesian_state.cpp
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 //-----------------------------------------------------------------------------
25 //-----------------------------------------------------------------------------
26 
28 #include <tf2_eigen/tf2_eigen.h>
29 #include "Eigen/src/Core/Matrix.h"
30 #include "geometry_msgs/Vector3.h"
31 
32 namespace my_tf2
33 {
34 geometry_msgs::Vector3 toMsg(const Eigen::Vector3d& in)
35 {
36  geometry_msgs::Vector3 msg;
37  msg.x = in.x();
38  msg.y = in.y();
39  msg.z = in.z();
40  return msg;
41 };
42 } // namespace my_tf2
43 
45 {
47 {
48  p = Eigen::Vector3d::Zero();
49  q.x() = 0;
50  q.y() = 0;
51  q.z() = 0;
52  q.w() = 1;
53 
54  v = Eigen::Vector3d::Zero();
55  v_dot = Eigen::Vector3d::Zero();
56 
57  w = Eigen::Vector3d::Zero();
58  w_dot = Eigen::Vector3d::Zero();
59 }
60 
61 CartesianState::CartesianState(const cartesian_control_msgs::CartesianTrajectoryPoint& point)
62 {
63  // Pose
64  tf2::fromMsg(point.pose.position, p);
65  tf2::fromMsg(point.pose.orientation, q);
66  if (q.coeffs() == Eigen::Vector4d::Zero())
67  {
68  q.w() = 1;
69  }
70  q.normalize();
71 
72  // Velocity
73  tf2::fromMsg(point.twist.linear, v);
74  tf2::fromMsg(point.twist.angular, w);
75 
76  // Acceleration
77  tf2::fromMsg(point.acceleration.linear, v_dot);
78  tf2::fromMsg(point.acceleration.angular, w_dot);
79 }
80 
82 {
83  CartesianState result;
84  result.p = p - other.p;
85  result.q = q * other.q.inverse();
86  result.v = v - other.v;
87  result.w = w - other.w;
88  result.v_dot = v_dot - other.v_dot;
89  result.w_dot = w_dot - other.w_dot;
90 
91  return result;
92 }
93 
94 cartesian_control_msgs::CartesianTrajectoryPoint CartesianState::toMsg(int time_from_start) const
95 {
96  cartesian_control_msgs::CartesianTrajectoryPoint point;
97 
98  // Pose
99  point.pose.position = tf2::toMsg(p);
100  point.pose.orientation = tf2::toMsg(q);
101 
102  // Velocity
103  point.twist.linear = my_tf2::toMsg(v);
104  point.twist.angular = my_tf2::toMsg(w);
105 
106  // Acceleration
107  point.acceleration.linear = my_tf2::toMsg(v_dot);
108  point.acceleration.angular = my_tf2::toMsg(w_dot);
109 
110  return point;
111 }
112 
113 std::ostream& operator<<(std::ostream& out, const CartesianState& state)
114 {
115  out << "p:\n" << state.p << '\n';
116  out << "q:\n" << state.q.coeffs() << '\n';
117  out << "v:\n" << state.v << '\n';
118  out << "w:\n" << state.w << '\n';
119  out << "v_dot:\n" << state.v_dot << '\n';
120  out << "w_dot:\n" << state.w_dot;
121  return out;
122 }
123 } // namespace ros_controllers_cartesian
ros_controllers_cartesian
Definition: cartesian_state.h:29
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
ros_controllers_cartesian::CartesianState::v
Eigen::Vector3d v
linear velocity,
Definition: cartesian_state.h:101
ros_controllers_cartesian::operator<<
std::ostream & operator<<(std::ostream &os, const CartesianTrajectorySegment::SplineState &state)
Stream operator for testing and debugging.
Definition: cartesian_trajectory_segment.cpp:180
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
my_tf2::toMsg
geometry_msgs::Vector3 toMsg(const Eigen::Vector3d &in)
Definition: cartesian_state.cpp:34
ros_controllers_cartesian::CartesianState::operator-
CartesianState operator-(const CartesianState &other) const
Difference operator between states.
Definition: cartesian_state.cpp:81
ros_controllers_cartesian::CartesianState
Cartesian state with pose, velocity and acceleration.
Definition: cartesian_state.h:38
cartesian_state.h
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
tf2::toMsg
B toMsg(const A &a)
my_tf2
Definition: cartesian_state.cpp:32


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