Namespaces | Macros | Functions
geometry_msgs.hpp File Reference

Specializations of getParam() for geometry_msgs. More...

#include <vector>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Point32.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/Vector3.h>
Include dependency graph for geometry_msgs.hpp:

Go to the source code of this file.

Namespaces

 cras
 

Macros

#define DEFINE_CONVERTING_GET_PARAM_ROS_VECTOR3(resultType, scalarType, defaultUnit)
 

Functions

 cras::DEFINE_CONVERTING_GET_PARAM (::geometry_msgs::Quaternion, ::std::vector< double >, "", [](const ::std::vector< double > &v) { if(v.size() !=3 &&v.size() !=4) throw ::std::runtime_error(::cras::format("Cannot load %s parameter from an array of length %lu", "geometry_msgs::Quaternion", v.size()));::geometry_msgs::Quaternion m;if(v.size()==4) { m.x=v[0];m.y=v[1];m.z=v[2];m.w=v[3];} else { ::tf2::Quaternion q;q.setRPY(v[0], v[1], v[2]);m.x=q.getX();m.y=q.getY();m.z=q.getZ();m.w=q.getW();} return m;}) DEFINE_CONVERTING_GET_PARAM(
 

Detailed Description

Specializations of getParam() for geometry_msgs.

Author
Martin Pecka SPDX-License-Identifier: BSD-3-Clause SPDX-FileCopyrightText: Czech Technical University in Prague

Quaternion can be loaded either from 4 values (direct coeffs) or 3 values (roll, pitch, yaw in rad).

Transform can be loaded either from 6 values (3 translation + 3 rotation), 7 values (3 translation + 4 rotation) or 16 values (column-wise transformation matrix).

Definition in file geometry_msgs.hpp.

Macro Definition Documentation

◆ DEFINE_CONVERTING_GET_PARAM_ROS_VECTOR3

#define DEFINE_CONVERTING_GET_PARAM_ROS_VECTOR3 (   resultType,
  scalarType,
  defaultUnit 
)
Value:
DEFINE_CONVERTING_GET_PARAM(resultType, std::vector<scalarType>, defaultUnit, [](const ::std::vector<scalarType>& v){ \
if (v.size() != 3) \
throw ::std::runtime_error( \
::cras::format("Cannot load %s parameter from an array of length %lu", #resultType, v.size())); \
resultType m; m.x = v[0]; m.y = v[1]; m.z = v[2]; \
return m; \
})

Definition at line 26 of file geometry_msgs.hpp.

DEFINE_CONVERTING_GET_PARAM
#define DEFINE_CONVERTING_GET_PARAM(resultType, paramServerType, defaultUnit, convertToResultFn)
Generate definitions of "specializations" of getParam(Verbose) that use different ResultType and Para...
Definition: param_utils.hpp:484
cras::format
inline ::std::string format(::std::string format,...)
Definition: string_utils.hpp:280


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:04