converter

Defines some helper functions to convert data from OMPL to ROS and vice versa.

namespace slope_constrained_planner
class Converter
#include <converter.h>

Helper class for converting data from OMPL to ROS and vice versa.

Public Functions

Converter(std::shared_ptr<ob::SE3StateSpace> space)

Constructor.

Parameters:

space – State space of the problem represented in SE3

ob::ScopedState poseRosToOmpl(const geometry_msgs::PoseStamped &pose_ros) const

Converts the pos data from type geometry_msgs::PoseStamped to SE3 state data type.

Parameters:

pose_ros – Position to be converted

nav_msgs::Path pathOmplToRos(const og::PathGeometric &path) const

Converts the found path by the planner to nav_msgs::Path data type.

Parameters:

path – Found solution by the planner in og::PathGeometric format

Private Members

std::shared_ptr<ob::SE3StateSpace> space_