conversion.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020, Christoph Rösmann, All rights reserved.
6  *
7  * This program is free software: you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation, either version 3 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <https://www.gnu.org/licenses/>.
19  *
20  * Authors: Christoph Rösmann
21  *********************************************************************/
22 
24 
25 #include <tf/tf.h>
26 
27 namespace mpc_local_planner {
28 
29 void convert(const corbo::TimeSeries& time_series, const RobotDynamicsInterface& dynamics, std::vector<geometry_msgs::PoseStamped>& poses_stamped,
30  const std::string& frame_id)
31 {
32  poses_stamped.clear();
33 
34  if (time_series.isEmpty()) return;
35 
36  for (int i = 0; i < time_series.getTimeDimension(); ++i)
37  {
38  poses_stamped.emplace_back();
39 
40  double theta = 0;
41  dynamics.getPoseSE2FromState(time_series.getValuesMap(i), poses_stamped.back().pose.position.x, poses_stamped.back().pose.position.y, theta);
42  poses_stamped.back().pose.orientation = tf::createQuaternionMsgFromYaw(theta);
43  poses_stamped.back().header.frame_id = frame_id;
44  poses_stamped.back().header.stamp = ros::Time::now(); // TODO(roesmann) should we use now()?
45  }
46 }
47 
48 } // namespace mpc_local_planner
void convert(const corbo::TimeSeries &time_series, const RobotDynamicsInterface &dynamics, std::vector< geometry_msgs::PoseStamped > &poses_stamped, const std::string &frame_id)
Convert TimeSeries to pose array.
Definition: conversion.cpp:29
int getTimeDimension() const
bool isEmpty() const
virtual void getPoseSE2FromState(const Eigen::Ref< const Eigen::VectorXd > &x, double &pos_x, double &pos_y, double &theta) const =0
Convert state vector to pose (x,y,theta)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
Eigen::Map< const Eigen::VectorXd > getValuesMap(int time_idx) const
static Time now()
Specialization of SystemDynamicsInterface for mobile robots.


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:53:18