conversion.h
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 
23 #ifndef UTILS_CONVERSION_H_
24 #define UTILS_CONVERSION_H_
25 
26 #include <corbo-core/time_series.h>
27 #include <corbo-core/types.h>
29 
30 #include <geometry_msgs/PoseStamped.h>
31 
32 #include <memory>
33 #include <string>
34 
35 namespace mpc_local_planner {
36 
51 void convert(const corbo::TimeSeries& time_series, const RobotDynamicsInterface& dynamics, std::vector<geometry_msgs::PoseStamped>& poses_stamped,
52  const std::string& frame_id);
53 
54 } // namespace mpc_local_planner
55 
56 #endif // UTILS_CONVERSION_H_
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


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