17 #include <geometry_msgs/Point.h> 18 #include <geometry_msgs/Point32.h> 19 #include <geometry_msgs/Quaternion.h> 20 #include <geometry_msgs/Transform.h> 21 #include <geometry_msgs/Vector3.h> 25 #define DEFINE_CONVERTING_GET_PARAM_ROS_VECTOR3(resultType, scalarType, defaultUnit) \ 26 DEFINE_CONVERTING_GET_PARAM(resultType, std::vector<scalarType>, defaultUnit, [](const ::std::vector<scalarType>& v){ \ 28 throw ::std::runtime_error( \ 29 ::cras::format("Cannot load %s parameter from an array of length %lu", #resultType, v.size())); \ 30 resultType m; m.x = v[0]; m.y = v[1]; m.z = v[2]; \ 39 if (v.size() != 3 && v.size() != 4)
40 throw ::std::runtime_error(::
cras::format(
"Cannot load %s parameter from an array of length %lu",
41 "geometry_msgs::Quaternion", v.size()));
42 ::geometry_msgs::Quaternion m;
45 m.x = v[0]; m.y = v[1]; m.z = v[2]; m.w = v[3];
50 m.x = q.getX(); m.y = q.getY(); m.z = q.getZ(); m.w = q.
getW();
56 if (v.size() != 6 && v.size() != 7 && v.size() != 16)
57 throw ::std::runtime_error(::
cras::format(
"Cannot load %s parameter from an array of length %lu",
58 "geometry_msgs::Transform", v.size()));
59 ::geometry_msgs::Transform m;
60 if (v.size() == 6 || v.size() == 7)
62 m.translation.x = v[0]; m.translation.y = v[1]; m.translation.z = v[2];
66 m.rotation.x = q.getX(); m.rotation.y = q.getY(); m.rotation.z = q.getZ(); m.rotation.w = q.
getW();
70 m.rotation.x = v[3]; m.rotation.y = v[4]; m.rotation.z = v[5]; m.rotation.w = v[6];
75 m.translation.x = v[3]; m.translation.y = v[7]; m.translation.z = v[11];
79 m.rotation.x = q.getX(); m.rotation.y = q.getY(); m.rotation.z = q.getZ(); m.rotation.w = q.
getW();
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
#define DEFINE_CONVERTING_GET_PARAM_ROS_VECTOR3(resultType, scalarType, defaultUnit)
TF2SIMD_FORCE_INLINE const tf2Scalar & getW() const
inline ::std::string format(const char *format, ::va_list args)
void getRotation(Quaternion &q) const
DEFINE_CONVERTING_GET_PARAM(::Eigen::Vector3d, ::std::vector< double >, "", [](const ::std::vector< double > &v){ checkSize(v, 3, "vector");return ::Eigen::Vector3d(v.data());}) DEFINE_CONVERTING_GET_PARAM(