ros_conversions.cpp
Go to the documentation of this file.
1 #include "ros_conversions.h"
2 
3 #include <math.h>
4 
5 #include <cmath>
6 #include <optional>
7 
8 #include <boost/none.hpp>
9 #include <boost/optional/optional.hpp>
10 #include <boost/smart_ptr/make_shared_object.hpp>
11 
16 
24 
25 #include <geometry_msgs/Twist.h>
26 #include <range/v3/view/drop.hpp>
27 #include <range/v3/view/zip.hpp>
28 #include <stuff/misc.h>
29 #include <teb_local_planner/costmap.h>
30 #include <teb_local_planner/penalty_models.h>
31 #include <teb_local_planner/pose_se2.h>
32 #include <teb_local_planner/timed_elastic_band.h>
33 
35 {
36  Eigen::Vector2d
37  toRos2D(const Eigen::Vector2f& vec)
38  {
39  return vec.cast<double>() / 1000; // [mm] to [m]
40  }
41 
42  Eigen::Vector2d
43  toRos(const Eigen::Vector3f& vec)
44  {
45  return conv::to2D(vec).cast<double>() / 1000; // [mm] to [m]
46  }
47 
48  Eigen::Vector3f
49  fromRos(const Eigen::Vector2d& vec)
50  {
51  return conv::to3D(vec.cast<float>()) * 1000; // [m] to [mm]
52  }
53 
54  teb_local_planner::PoseSE2
55  toRos(const core::Pose& pose)
56  {
57  core::Pose2D pose2D = to2D(pose);
58  return toRos(pose2D);
59  }
60 
61  teb_local_planner::PoseSE2
62  toRos(const core::Pose2D& pose)
63  {
64  Eigen::Vector2d pos = pose.translation().cast<double>();
65  double theta = Eigen::Rotation2Df(pose.linear()).angle();
66 
67  // we change it such that x is pointing forward.
68  // ROS: x pointing forward, ArmarX: y pointing forward
69  theta += M_PI_2;
70  // normalize angle
71  theta = g2o::normalize_theta(theta);
72 
73  return {pos / 1000., theta}; // [mm] to [m]
74  }
75 
77  fromRos(const teb_local_planner::PoseSE2& pose)
78  {
79  Eigen::Vector2d pos = pose.position() * 1000; // [m] to [mm]
80  double theta = pose.theta();
81 
82  // we change it such that x is pointing forward.
83  // ROS: x pointing forward, ArmarX: y pointing forward
84  theta -= M_PI_2;
85 
86 
88  ret.translation() = pos.cast<float>();
89  ret.linear() = Eigen::Rotation2Df(theta).toRotationMatrix();
90 
91  return to3D(ret);
92  }
93 
94  geometry_msgs::Twist
95  toRos(const core::Twist& velocity)
96  {
97  geometry_msgs::Twist ret;
98 
99  // we change it such that x is pointing forward.
100  // ROS: x pointing forward, ArmarX: y pointing forward
101 
102  ret.linear.x = velocity.linear.y() / 1000; // [mm] to [m]
103  ret.linear.y = -velocity.linear.x() / 1000; // [mm] to [m]
104  ret.angular.z = velocity.angular.z();
105 
106  return ret;
107  }
108 
109  teb_local_planner::TimedElasticBand
110  toRos(const core::GlobalTrajectory& trajectory)
111  {
112  teb_local_planner::TimedElasticBand teb;
113 
114  bool first = true;
115  teb_local_planner::PoseSE2 lastPose;
116  for (const core::GlobalTrajectoryPoint& point : trajectory.points())
117  {
118  teb_local_planner::PoseSE2 pose = toRos(point.waypoint.pose);
119  teb.addPose(pose);
120 
121  if (!first)
122  {
123  Eigen::Vector2d distance = pose.position() - lastPose.position();
124  double timeDiff = distance.norm() / (point.velocity / 1000); // [mm/s] -> [m/s]
125  teb.addTimeDiff(timeDiff);
126 
127  first = false;
128  }
129 
130  lastPose = pose;
131  }
132 
133  return teb;
134  }
135 
137  fromRos(const teb_local_planner::TimedElasticBand& teb)
138  {
139  const auto& tebPoses = teb.poses();
140 
141  if (tebPoses.empty())
142  {
143  return {};
144  }
145 
146  core::LocalTrajectoryPoints trajectory;
147  trajectory.reserve(tebPoses.size());
148 
149  // TODO this timestamp should be given via the argument list
150  DateTime timestamp = Clock::Now();
151 
152  ARMARX_CHECK_EQUAL(tebPoses.size() - 1, teb.timediffs().size());
153 
154  // add the first pose at this timestamp
155  trajectory.push_back(core::LocalTrajectoryPoint{
156  .timestamp = timestamp, .pose = {fromRos(tebPoses.front()->pose())}});
157 
158  // all consecutive poses
159  for (const auto& [poseVertex, timediff] :
160  ranges::views::zip(tebPoses | ranges::views::drop(1), teb.timediffs()))
161  {
162  const core::Pose pose = fromRos(poseVertex->pose());
163  const Duration dt = Duration::SecondsDouble(timediff->dt());
164 
165  timestamp += dt;
166  trajectory.push_back(
167  core::LocalTrajectoryPoint{.timestamp = timestamp, .pose = {pose}});
168  }
169 
170  ARMARX_CHECK_EQUAL(trajectory.size(), tebPoses.size());
171 
172  return {trajectory};
173  }
174 
177  {
178  // a,b parameter are along the x and y axis respectively
179  // ROS and ArmarX have the x axis pointing in a different direction
180  // ROS: x pointing forward, ArmarX: y pointing forward
181  return {.a = ellipse.b / 1000, .b = ellipse.a / 1000}; // [mm] to [m]
182  }
183 
184  teb_local_planner::Costmap
185  toRos(const algorithms::Costmap& costmap)
186  {
187  const algorithms::Costmap::Parameters& params = costmap.params();
188  const teb_local_planner::Costmap::Parameters teb_params = {
189  .binaryGrid = params.binaryGrid, .cellSize = params.cellSize / 1000}; // [mm] to [m]
190 
191  const algorithms::SceneBounds& bounds = costmap.getLocalSceneBounds();
192  const teb_local_planner::Costmap::SceneBounds teb_bounds = {
193  .min = toRos2D(bounds.min).cast<float>(), .max = toRos2D(bounds.max).cast<float>()};
194 
195  const std::optional<algorithms::Costmap::Mask>& mask = costmap.getMask();
196  boost::optional<teb_local_planner::Costmap::Mask> teb_mask = boost::none;
197  if (mask)
198  {
199  teb_mask = mask.value();
200  }
201 
202  teb_local_planner::Costmap::Pose2D teb_origin = costmap.origin();
203  teb_origin.translation() /= 1000; // [mm] to[m]
204 
205  algorithms::Costmap::Grid teb_grid = costmap.getGrid();
206  teb_grid /= 1000; // [mm] to [m]
207 
208  return teb_local_planner::Costmap{teb_grid, teb_params, teb_bounds, teb_mask, teb_origin};
209  }
210 
211  teb_local_planner::PenaltyModelPtr
213  {
214  return boost::make_shared<teb_local_planner::LinearPenaltyModel>(
215  teb_local_planner::LinearPenaltyModel(model.minDistance, model.epsilon));
216  }
217 
218  teb_local_planner::PenaltyModelPtr
220  {
221  return boost::make_shared<teb_local_planner::ExponentialPenaltyModel>(
222  teb_local_planner::LinearPenaltyModel(model.minDistance, model.epsilon),
223  model.exponent);
224  }
225 
226 } // namespace armarx::navigation::conv
armarx::navigation::algorithms::Costmap::getMask
const std::optional< Mask > & getMask() const noexcept
Definition: Costmap.cpp:399
armarx::navigation::core::GlobalTrajectory
Definition: Trajectory.h:70
armarx::navigation::human::ExponentialPenaltyModel::minDistance
float minDistance
Definition: types.h:70
armarx::aron::ret
ReaderT::InputType T & ret
Definition: rw.h:13
armarx::navigation::core::Pose
Eigen::Isometry3f Pose
Definition: basic_types.h:31
armarx::navigation::human::LinearPenaltyModel
Definition: types.h:62
basic_types.h
DateTime.h
armarx::navigation::human::ExponentialPenaltyModel
Definition: types.h:68
armarx::max
std::vector< T > max(const std::vector< T > &v1, const std::vector< T > &v2)
Definition: VectorHelpers.h:297
armarx::navigation::core::LocalTrajectoryPoint::timestamp
DateTime timestamp
Definition: Trajectory.h:158
Duration.h
types.h
armarx::navigation::core::LocalTrajectoryPoints
std::vector< LocalTrajectoryPoint > LocalTrajectoryPoints
Definition: Trajectory.h:162
armarx::navigation::algorithms::Costmap::Grid
Eigen::MatrixXf Grid
Definition: Costmap.h:56
armarx::skills::gui::Parameters
aron::data::DictPtr Parameters
Definition: SkillManagerWrapper.h:21
armarx::navigation::conv::fromRos
Eigen::Vector3f fromRos(const Eigen::Vector2d &vec)
Definition: ros_conversions.cpp:49
armarx::navigation::core::GlobalTrajectoryPoint
Definition: Trajectory.h:37
armarx::navigation::human::ExponentialPenaltyModel::exponent
float exponent
Definition: types.h:72
armarx::navigation::algorithms::Costmap::getLocalSceneBounds
const SceneBounds & getLocalSceneBounds() const noexcept
Definition: Costmap.cpp:130
armarx::navigation::core::Pose2D
Eigen::Isometry2f Pose2D
Definition: basic_types.h:34
Clock.h
armarx::navigation::core::Twist
Definition: basic_types.h:53
Costmap.h
armarx::navigation::conv
This file is part of ArmarX.
Definition: eigen.cpp:10
armarx::navigation::core::LocalTrajectoryPoint
Definition: Trajectory.h:156
armarx::navigation::human::shapes::Ellipse::b
float b
Definition: shapes.h:37
armarx::navigation::algorithms::Costmap::Parameters::binaryGrid
bool binaryGrid
Definition: Costmap.h:27
armarx::navigation::human::ExponentialPenaltyModel::epsilon
float epsilon
Definition: types.h:71
armarx::navigation::algorithms::Costmap::params
const Parameters & params() const noexcept
Definition: Costmap.cpp:237
armarx::navigation::conv::toRos
Eigen::Vector2d toRos(const Eigen::Vector3f &vec)
Definition: ros_conversions.cpp:43
armarx::core::time::Duration::SecondsDouble
static Duration SecondsDouble(double seconds)
Constructs a duration in seconds.
Definition: Duration.cpp:78
armarx::navigation::algorithms::Costmap::getGrid
const Grid & getGrid() const
Definition: Costmap.cpp:243
armarx::navigation::core::LocalTrajectory
Definition: Trajectory.h:170
armarx::navigation::conv::toRos2D
Eigen::Vector2d toRos2D(const Eigen::Vector2f &vec)
Definition: ros_conversions.cpp:37
armarx::navigation::algorithms::SceneBounds
Definition: types.h:29
armarx::navigation::conv::to2D
std::vector< Eigen::Vector2f > to2D(const std::vector< Eigen::Vector3f > &v)
Definition: eigen.cpp:29
ExpressionException.h
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
armarx::navigation::core::Twist::linear
LinearVelocity linear
Definition: basic_types.h:55
shapes.h
armarx::navigation::algorithms::SceneBounds::min
Eigen::Vector2f min
Definition: types.h:31
armarx::navigation::human::LinearPenaltyModel::epsilon
float epsilon
Definition: types.h:65
armarx::core::time::Duration
Represents a duration.
Definition: Duration.h:16
armarx::navigation::algorithms::Costmap::Parameters::cellSize
float cellSize
How big each cell is in the uniform grid.
Definition: Costmap.h:30
armarx::navigation::conv::to3D
std::vector< Eigen::Vector3f > to3D(const std::vector< Eigen::Vector2f > &v)
Definition: eigen.cpp:14
armarx::navigation::human::shapes::Ellipse
An axis oriented ellipse with half-axes a and b along the x- and y-axis respectively.
Definition: shapes.h:34
armarx::navigation::algorithms::Costmap::Parameters
Definition: Costmap.h:24
armarx::navigation::core::Twist::angular
AngularVelocity angular
Definition: basic_types.h:56
armarx::core::time::Clock::Now
static DateTime Now()
Current time on the virtual clock.
Definition: Clock.cpp:93
distance
double distance(const Point &a, const Point &b)
Definition: point.hpp:95
armarx::navigation::algorithms::Costmap::origin
const core::Pose2D & origin() const
Definition: Costmap.h:143
eigen.h
ARMARX_CHECK_EQUAL
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
Definition: ExpressionException.h:130
Trajectory.h
armarx::navigation::core::GlobalTrajectory::points
const std::vector< GlobalTrajectoryPoint > & points() const
Definition: Trajectory.cpp:734
armarx::navigation::human::shapes::Ellipse::a
float a
Definition: shapes.h:36
types.h
armarx::navigation::algorithms::SceneBounds::max
Eigen::Vector2f max
Definition: types.h:32
armarx::navigation::human::LinearPenaltyModel::minDistance
float minDistance
Definition: types.h:64
dt
constexpr T dt
Definition: UnscentedKalmanFilterTest.cpp:45
armarx::navigation::algorithms::Costmap
Definition: Costmap.h:16
ros_conversions.h