30 #include <geometry_msgs/Twist.h>
31 #include <teb_local_planner/costmap.h>
32 #include <teb_local_planner/penalty_models.h>
33 #include <teb_local_planner/pose_se2.h>
34 #include <teb_local_planner/timed_elastic_band.h>
39 Eigen::Vector2d
toRos2D(
const Eigen::Vector2f& vec);
41 Eigen::Vector2d
toRos(
const Eigen::Vector3f& vec);
42 Eigen::Vector3f
fromRos(
const Eigen::Vector2d& vec);
49 geometry_msgs::Twist
toRos(
const core::Twist& velocity);
51 teb_local_planner::TimedElasticBand
toRos(
const core::GlobalTrajectory& trajectory);
53 core::LocalTrajectory
fromRos(
const teb_local_planner::TimedElasticBand& teb);
55 human::shapes::Ellipse
toRos(
const human::shapes::Ellipse& ellipse);
57 teb_local_planner::Costmap
toRos(
const algorithms::Costmap& costmap);
59 teb_local_planner::PenaltyModelPtr
toRos(
const human::LinearPenaltyModel& model);
61 teb_local_planner::PenaltyModelPtr
toRos(
const human::ExponentialPenaltyModel& model);