|
| __attribute__ ((format(printf, 1, 0))) inline |
|
| __attribute__ ((format(printf, 1, 2))) inline |
|
::std::string | appendIfNonEmpty (const ::std::string &str, const ::std::string &suffix) |
|
auto | bind_front (F &&f, Args &&... args) |
|
::std::string | cleanTypeName (const ::std::string &typeName) |
|
bool | contains (const ::std::string &str, char c) |
|
bool | contains (const ::std::string &str, const ::std::string &needle) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::dynamic_reconfigure::Config &v, bool skipNonConvertible, ::std::list<::std::string > *errors) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::std::array< T, N > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::std::list< T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::std::map<::std::string, T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::std::set< T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::std::unordered_map<::std::string, T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::std::unordered_set< T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::std::vector< T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, ::XmlRpc::XmlRpcValue &v, bool=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, bool &v, bool=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, double &v, bool=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, int &v, bool=false, ::std::list<::std::string > *errors=nullptr) |
|
bool | convert (const ::XmlRpc::XmlRpcValue &x, std::string &v, bool=false, ::std::list<::std::string > *errors=nullptr) |
|
D1 | convertDuration (const D2 &duration) |
|
T1 | convertTime (const T2 &time) |
|
void | copyChannelData (const ::cras::Cloud &in, ::cras::Cloud &out, const ::std::string &fieldName) |
|
void | copyShapeShifter (const ::topic_tools::ShapeShifter &in, ::topic_tools::ShapeShifter &out) |
| Copy in ShapeShifter to out . More...
|
|
void | copyShapeShifter (const topic_tools::ShapeShifter &in, topic_tools::ShapeShifter &out) |
|
| 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( |
|
| DEFINE_CONVERTING_GET_PARAM (::Eigen::Vector4d, ::std::vector< double >, "",[](const ::std::vector< double > &v){ checkSize(v, 4, "vector");return ::Eigen::Vector4d(v.data());}) DEFINE_CONVERTING_GET_PARAM( |
|
| 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( |
|
| DEFINE_CONVERTING_GET_PARAM (::tf2::Vector3, ::std::vector< double >, "",[](const ::std::vector< double > &v) { if(v.size() !=3) throw ::std::runtime_error(::cras::format("Cannot load %s parameter from an array of length %lu", "tf2::Vector3", v.size()));return ::tf2::Vector3(v[0], v[1], v[2]);}) DEFINE_CONVERTING_GET_PARAM( |
|
LONG_MAX | DEFINE_INTEGRAL_CONVERT (long long, int, LONG_LONG_MIN, LONG_LONG_MAX) DEFINE_INTEGRAL_CONVERT(unsigned short |
|
| DEFINE_INTEGRAL_CONVERT (short, int, SHRT_MIN, SHRT_MAX) DEFINE_INTEGRAL_CONVERT(long |
|
LONG_MAX USHRT_MAX | DEFINE_INTEGRAL_CONVERT (unsigned long, int, 0, ULONG_MAX) DEFINE_INTEGRAL_CONVERT(unsigned long long |
|
::std::string | demangle (const ::std::string &mangled) |
|
bool | endsWith (const ::std::string &str, const ::std::string &suffix) |
|
inline ::std::string | format (::std::string format, ::va_list args) |
|
inline ::std::string | format (::std::string format,...) |
|
double | frequency (const ::ros::Rate &rate, bool maxCycleTimeMeansZero=false) |
|
double | frequency (const ::ros::WallRate &rate, bool maxCycleTimeMeansZero=false) |
|
inline ::cras::from_chars_result | from_chars (const ::std::string &string, double &value, ::cras::chars_format fmt=::cras::chars_format::general) noexcept |
|
inline ::cras::from_chars_result | from_chars (const ::std::string &string, float &value, ::cras::chars_format fmt=::cras::chars_format::general) noexcept |
|
::cras::from_chars_result | from_chars (const char *first, const char *last, double &value, ::cras::chars_format fmt=::cras::chars_format::general) noexcept |
|
::cras::from_chars_result | from_chars (const char *first, const char *last, float &value, ::cras::chars_format fmt=::cras::chars_format::general) noexcept |
|
::cras::expected<::ros::Time, ::std::string > | fromStructTm (const ::tm &time) |
|
uint8_t * | getBuffer (::topic_tools::ShapeShifter &msg) |
| Get the internal buffer with serialized message data. More...
|
|
const uint8_t * | getBuffer (const ::topic_tools::ShapeShifter &msg) |
| Get the internal buffer with serialized message data. More...
|
|
const uint8_t * | getBuffer (const topic_tools::ShapeShifter &msg) |
|
uint8_t * | getBuffer (topic_tools::ShapeShifter &msg) |
|
size_t | getBufferLength (const ::topic_tools::ShapeShifter &msg) |
| Get the length of the internal buffer with serialized message data. More...
|
|
size_t | getBufferLength (const topic_tools::ShapeShifter &msg) |
|
::sensor_msgs::PointField & | getField (::cras::Cloud &cloud, const ::std::string &fieldName) |
|
const ::sensor_msgs::PointField & | getField (const ::cras::Cloud &cloud, const ::std::string &fieldName) |
|
::cras::optional<::std_msgs::Header > | getHeader (const ::topic_tools::ShapeShifter &msg) |
| Get the header field of the given message, if it has any. More...
|
|
cras::optional< std_msgs::Header > | getHeader (const topic_tools::ShapeShifter &msg) |
|
inline ::std::string | getParam (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}, const ::cras::LogHelper *const logger=nullptr) |
|
ResultType | getParam (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr) |
|
inline ::std::string | getParam (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}, const ::cras::LogHelper *const logger=nullptr) |
|
ResultType | getParam (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr) |
|
inline ::std::string | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
|
ResultType | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
|
inline ::std::string | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions< std::string > &options={}) |
|
ResultType | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
|
inline ::cras::GetParamResult<::std::string > | getParamVerbose (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}, const ::cras::LogHelper *const logger=nullptr) |
|
inline ::cras::GetParamResult< ResultType > | getParamVerbose (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr) |
|
inline ::cras::GetParamResult<::std::string > | getParamVerbose (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}, const ::cras::LogHelper *const logger=nullptr) |
|
inline ::cras::GetParamResult< ResultType > | getParamVerbose (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr) |
|
GetParamResult<::std::string > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
|
GetParamResult< ResultType > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
|
GetParamResult<::std::string > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
|
GetParamResult< ResultType > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
|
double | getPitch (const ::geometry_msgs::Quaternion &quat) |
|
double | getPitch (const ::tf2::Quaternion &quat) |
|
double | getRoll (const ::geometry_msgs::Quaternion &quat) |
|
double | getRoll (const ::tf2::Quaternion &quat) |
|
void | getRPY (const ::geometry_msgs::Quaternion &quat, double &roll, double &pitch, double &yaw) |
|
void | getRPY (const ::tf2::Quaternion &quat, double &roll, double &pitch, double &yaw) |
|
std::string | getThreadName () |
|
inline ::std::string | getTypeName () |
|
::std::string | getTypeName (const ::std::type_info &typeInfo) |
|
double | getYaw (const ::geometry_msgs::Quaternion &quat) |
|
double | getYaw (const ::tf2::Quaternion &quat) |
|
int | getYear (const ::ros::SteadyTime &time) |
|
int | getYear (const ::ros::Time &time) |
|
int | getYear (const ::ros::WallTime &time) |
|
bool | hasField (const ::cras::Cloud &cloud, const ::std::string &fieldName) |
|
bool | hasHeader (const ::topic_tools::ShapeShifter &msg) |
| Tell whether the given message has header field. More...
|
|
bool | hasHeader (const topic_tools::ShapeShifter &msg) |
|
::std::string | iconvConvert (const ::std::string &toEncoding, const ::std::string &fromEncoding, const ::std::string &inText, bool translit=false, bool ignore=false, double initialOutbufSizeScale=1.0, double outbufEnlargeCoef=2.0, const ::cras::optional<::std::string > &localeName=::cras::nullopt) |
|
bool | isLegalBaseName (const ::std::string &name) |
|
bool | isLegalName (const ::std::string &name) |
|
bool | isNodeletUnloading (const ::nodelet::Nodelet &nodelet) |
|
bool | isSetIntersectionEmpty (const ::std::set< T > &set1, const ::std::set< T > &set2) |
|
::std::string | join (const T &strings, const ::std::string &delimiter) |
|
int8_t | logLevelToRosgraphMsgLevel (::ros::console::Level rosLevel) |
|
::boost::shared_ptr< T > | make_shared_from_fast_pool (Args &&... args) |
|
::boost::shared_ptr< T > | make_shared_from_pool (Args &&... args) |
|
template<typename T , typename EnableT > |
void | msgToShapeShifter (const T &msg, ::topic_tools::ShapeShifter &shifter) |
| Copy the message instance into the given ShapeShifter. More...
|
|
inline ::cras::BoundParamHelperPtr | nodeParams (const ::ros::NodeHandle &node, const ::std::string &ns="") |
|
::ros::Time | nowFallbackToWall () |
|
size_t | numPoints (const ::cras::Cloud &cloud) |
|
uint8_t * | outputByteBuffer (allocator_t allocator, const std::vector< uint8_t > &bytes) |
|
uint8_t * | outputByteBuffer (allocator_t allocator, const uint8_t *bytes, size_t length) |
|
uint8_t * | outputRosMessage (allocator_t allocator, const Message &msg) |
|
char * | outputString (allocator_t allocator, const char *string, size_t length) |
|
char * | outputString (allocator_t allocator, const std::string &string) |
|
inline ::cras::BoundParamHelperPtr | paramsForNodeHandle (const ::ros::NodeHandle &node) |
|
double | parseDouble (const ::std::string &string) |
|
double | parseDouble (const char *string) |
|
D | parseDuration (const ::std::string &s) |
|
float | parseFloat (const ::std::string &string) |
|
float | parseFloat (const char *string) |
|
int16_t | parseInt16 (const char *string) |
|
int16_t | parseInt16 (const char *string, const uint8_t base) |
|
int16_t | parseInt16 (const std::string &string) |
|
int16_t | parseInt16 (const std::string &string, uint8_t base) |
|
int32_t | parseInt32 (const char *string) |
|
int32_t | parseInt32 (const char *string, const uint8_t base) |
|
int32_t | parseInt32 (const std::string &string) |
|
int32_t | parseInt32 (const std::string &string, uint8_t base) |
|
int64_t | parseInt64 (const char *string) |
|
int64_t | parseInt64 (const char *string, const uint8_t base) |
|
int64_t | parseInt64 (const std::string &string) |
|
int64_t | parseInt64 (const std::string &string, uint8_t base) |
|
int8_t | parseInt8 (const char *string) |
|
int8_t | parseInt8 (const char *string, const uint8_t base) |
|
int8_t | parseInt8 (const std::string &string) |
|
int8_t | parseInt8 (const std::string &string, uint8_t base) |
|
T | parseTime (const ::std::string &s, const ::cras::optional< typename ::cras::DurationType< T >::value > &timezoneOffset={}, const T &referenceDate={}) |
|
D | parseTimezoneOffset (const ::std::string &s) |
|
uint16_t | parseUInt16 (const char *string) |
|
uint16_t | parseUInt16 (const char *string, const uint8_t base) |
|
uint16_t | parseUInt16 (const std::string &string) |
|
uint16_t | parseUInt16 (const std::string &string, uint8_t base) |
|
uint32_t | parseUInt32 (const char *string) |
|
uint32_t | parseUInt32 (const char *string, const uint8_t base) |
|
uint32_t | parseUInt32 (const std::string &string) |
|
uint32_t | parseUInt32 (const std::string &string, uint8_t base) |
|
uint64_t | parseUInt64 (const char *string) |
|
uint64_t | parseUInt64 (const char *string, const uint8_t base) |
|
uint64_t | parseUInt64 (const std::string &string) |
|
uint64_t | parseUInt64 (const std::string &string, uint8_t base) |
|
uint8_t | parseUInt8 (const char *string) |
|
uint8_t | parseUInt8 (const char *string, const uint8_t base) |
|
uint8_t | parseUInt8 (const std::string &string) |
|
uint8_t | parseUInt8 (const std::string &string, uint8_t base) |
|
::std::string | prependIfNonEmpty (const ::std::string &str, const ::std::string &prefix) |
|
inline ::std::string | quoteIfStringType (const ::std::string &s, const T &) |
|
void | registerCloudChannelType (const ::std::string &channelPrefix, ::cras::CloudChannelType type) |
|
::ros::Duration | remainingTime (const ::ros::Time &query, const ::ros::Duration &timeout) |
|
::ros::Duration | remainingTime (const ::ros::Time &query, double timeout) |
|
::std::string | removePrefix (const ::std::string &str, const ::std::string &prefix, bool *hadPrefix=nullptr) |
|
::std::string | removeSuffix (const ::std::string &str, const ::std::string &suffix, bool *hadSuffix=nullptr) |
|
void | replace (::std::string &str, const ::std::string &from, const ::std::string &to, const ::cras::ReplacePosition &where=::cras::ReplacePosition::EVERYWHERE) |
|
::std::string | replace (const ::std::string &str, const ::std::string &from, const ::std::string &to, const ::cras::ReplacePosition &where=::cras::ReplacePosition::EVERYWHERE) |
|
void | resizeBuffer (::topic_tools::ShapeShifter &msg, size_t newLength) |
| Resize the internal buffer of the message. More...
|
|
void | resizeBuffer (topic_tools::ShapeShifter &msg, size_t newLength) |
|
::ros::console::Level | rosgraphMsgLevelToLogLevel (uint8_t msgLevel) |
|
::ros::Rate | safeRate (double frequency) |
|
::ros::WallRate | safeWallRate (double frequency) |
|
::ros::SteadyTime | saturateAdd (const ::ros::SteadyTime &time, const ::ros::WallDuration &duration) |
|
::ros::Time | saturateAdd (const ::ros::Time &time, const ::ros::Duration &duration) |
|
::ros::WallTime | saturateAdd (const ::ros::WallTime &time, const ::ros::WallDuration &duration) |
|
bool | setHeader (::topic_tools::ShapeShifter &msg, ::std_msgs::Header &header) |
| Change the header field of the given message, if it has any. More...
|
|
bool | setHeader (topic_tools::ShapeShifter &msg, std_msgs::Header &header) |
|
void | setThreadName (const std::string &name) |
|
size_t | sizeOfPointField (const ::sensor_msgs::PointField &field) |
|
size_t | sizeOfPointField (int datatype) |
|
::std::vector<::std::string > | split (const ::std::string &str, const ::std::string &delimiter, int maxSplits=-1) |
|
bool | startsWith (const ::std::string &str, const ::std::string &prefix) |
|
void | strip (::std::string &s, const char &c=' ') |
|
::std::string | strip (const ::std::string &s, const char &c=' ') |
|
void | stripLeading (::std::string &s, const char &c=' ') |
|
::std::string | stripLeading (const ::std::string &s, const char &c=' ') |
|
void | stripLeadingSlash (::std::string &s, bool warn=false) |
|
::std::string | stripLeadingSlash (const ::std::string &s, bool warn=false) |
|
void | stripTrailing (::std::string &s, const char &c=' ') |
|
::std::string | stripTrailing (const ::std::string &s, const char &c=' ') |
|
constexpr const char * | to_cstring (const ::XmlRpc::XmlRpcValue::Type &value) |
|
::std::string | to_pretty_string (const T &value) |
|
inline ::std::string | to_string (char *value) |
|
inline ::std::string | to_string (const ::Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols > &value) |
|
inline ::std::string | to_string (const ::Eigen::RotationBase< Derived, Dim > &value) |
|
inline ::std::string | to_string (const ::Eigen::Transform< Scalar, Dim, Mode, Options > &value) |
|
inline ::std::string | to_string (const ::std::array< T, N > &value) |
|
inline ::std::string | to_string (const ::std::map< K, V > &value) |
|
inline ::std::string | to_string (const ::std::string &value) |
|
inline ::std::string | to_string (const ::std::unordered_map< K, V > &value) |
|
inline ::std::string | to_string (const ::tf2::Matrix3x3 &value) |
|
inline ::std::string | to_string (const ::tf2::Quaternion &value) |
|
inline ::std::string | to_string (const ::tf2::Transform &value) |
|
inline ::std::string | to_string (const ::tf2::Vector3 &value) |
|
inline ::std::string | to_string (const ::XmlRpc::XmlRpcValue &value) |
|
inline ::std::string | to_string (const ::XmlRpc::XmlRpcValue::Type &value) |
|
inline ::std::string | to_string (const bool &value) |
|
inline ::std::string | to_string (const char *value) |
|
inline ::std::string | to_string (const char value[I]) |
|
inline ::std::string | to_string (const double &value) |
|
inline ::std::string | to_string (const float &value) |
|
inline ::std::string | to_string (const long double &value) |
|
std::string | to_string (const M &msg) |
|
inline ::std::string | to_string (const T &value) |
|
::Eigen::Isometry3d | toEigen (const ::urdf::Pose &pose) |
|
::Eigen::Quaterniond | toEigen (const ::urdf::Rotation &rotation) |
|
::Eigen::Translation3d | toEigen (const ::urdf::Vector3 &position) |
|
::std::string | toLower (const ::std::string &str) |
|
inline ::tm | toStructTm (const ::ros::SteadyTime &time) |
|
::tm | toStructTm (const ::ros::Time &time) |
|
inline ::tm | toStructTm (const ::ros::WallTime &time) |
|
::std::string | toUpper (const ::std::string &str) |
|
::urdf::Pose | toURDF (const ::Eigen::Isometry3d &pose) |
|
::urdf::Rotation | toURDF (const ::Eigen::Quaterniond &rotation) |
|
::urdf::Vector3 | toURDF (const ::Eigen::Translation3d &translation) |
|
::urdf::Vector3 | toURDF (const ::Eigen::Vector3d &vector) |
|
::std::string | toValidRosName (const ::std::string &text, bool baseName=true, const ::cras::optional<::std::string > &fallbackName=::cras::nullopt) |
|
void | transformChannel (::sensor_msgs::PointCloud2 &cloud, const ::geometry_msgs::Transform &transform, const ::std::string &channelPrefix, ::cras::CloudChannelType type) |
|
::sensor_msgs::PointCloud2 & | transformOnlyChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf, const ::std::unordered_map<::std::string, ::cras::CloudChannelType > &channels) |
|
::sensor_msgs::PointCloud2 & | transformOnlyXYZ (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf) |
|
::sensor_msgs::PointCloud2 & | transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf) |
|
::sensor_msgs::PointCloud2 & | transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf, const ::std::unordered_map<::std::string, ::cras::CloudChannelType > &channels) |
|
::sensor_msgs::PointCloud2 & | transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::tf2_ros::Buffer &tfBuffer, const ::std::string &targetFrame) |
|
::sensor_msgs::PointCloud2 & | transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::tf2_ros::Buffer &tfBuffer, const ::std::string &targetFrame, const ::std::unordered_map<::std::string, ::cras::CloudChannelType > &channels) |
|
::std::string | transliterateToAscii (const ::std::string &text) |
|
void | unregisterCloudChannelType (const ::std::string &channelPrefix) |
|