Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
cras Namespace Reference

Namespaces

 impl
 

Classes

class  BoundParamHelper
 Bound param helper (allows omitting the param adapter in each getParam call). More...
 
struct  DefaultParamServerType
 Default ParamServerType for the given ResultType. More...
 
struct  DefaultToParamFn
 Default function for converting XmlRpcValue to an intermediate value of type ParamServerType. More...
 
struct  DefaultToResultFn
 Default function for converting param server types to result types. More...
 
class  DiagnosedPublisher
 Wrapper for ROS publisher that automatically diagnoses the rate and delay of published messages. More...
 
class  DiagnosedPubSub
 Base for ROS publisher and subscriber with automatic message rate and delay diagnostics. More...
 
class  DiagnosedSubscriber
 Wrapper for ROS subscriber that automatically diagnoses the rate and delay of received messages. More...
 
class  DiagnosticUpdater
 Diagnostic updater that automatically sets its Hardware ID to hostname of the machine. More...
 
class  DurationStatus
 Diagnostic task for topic frequency and timestamp delay (combining FrequencyStatus and TimeStampStatus tasks). More...
 
struct  DurationStatusParam
 Parameters of DurationStatus diagnostic task. More...
 
class  FilterBase
 
class  FilterChain
 
class  FilterChainDiagnostics
 Diagnostics of performance of a filter chain. More...
 
class  FilterChainNodelet
 A versatile nodelet that can load and run a filter chain. More...
 
struct  FilterGetParamAdapter
 
class  FilterLogHelper
 
class  FrequencyStatusParam
 An extension of diagnostic_updater::FrequencyStatusParam that allows passing non-pointer min/max frequency values. If the internal pointers are used, they are correctly handled when copying this object (the new copy will have its own copy of the internal pointers). More...
 
struct  from_chars_result
 
struct  GetParamAdapter
 An adapter that allows getting ROS parameters from various sources. More...
 
class  GetParamException
 Exception thrown when conversion of a parameter fails during getParam() if option throwIfConvertFails is true or when a missing parameter is required. More...
 
struct  GetParamOptions
 Options specifying behavior of getParam() calls. More...
 
struct  GetParamResult
 Wrapper for the result of a getParam() call. It is designed to autoconvert to the result type sometimes. More...
 
struct  GetParamResultInfo
 Detailed information about the executed getParam() call. More...
 
class  HasLogger
 Convenience base class for providing this->log and getCrasLogger(). Just add it as a base to your class and all CRAS_* logging macros should work with the logger from this class. More...
 
struct  InterruptibleSleepInterface
 Interface to an object whose sleep() calls can be interrupted externally. Multiple sleep() calls can be happening at a time. The object waits for the last sleep() call to finish on destruction. No more sleep() calls can be made once destruction of the object started (sleep() will return false in such case). Make sure that ok() returns false when this object is about to be destroyed. More...
 
class  InterruptibleTFBuffer
 Provides overrides of canTransform() that can be interrupted. Normally, canTransform() waits until transform is available, timeout is reached (which may be never in paused simulation), time jumps backwards or ros::ok() returns false. This buffer adds another option of interrupting the call. It also allows "wrapping around" another buffer that does not support this interruptibility and add this ability to it. More...
 
struct  is_any
 Type trait determining whether type T is cras::any or not. More...
 
struct  is_any<::cras::any >
 Type trait determining whether type T is cras::any or not. More...
 
struct  is_c_string
 Type trait for dynamic-sized and constant-sized C strings. More...
 
struct  is_c_string< char * >
 
struct  is_c_string< char *const >
 
struct  is_c_string< char[I]>
 
struct  is_c_string< const char * >
 
struct  is_c_string< const char *const >
 
struct  is_c_string< const char[I]>
 
struct  is_cras_expected
 Type trait determining whether type T is cras::expected or not. More...
 
struct  is_cras_expected<::cras::expected< T, E > >
 Type trait determining whether type T is cras::optional or not. More...
 
struct  is_optional
 Type trait determining whether type T is cras::optional or not. More...
 
struct  is_optional<::cras::optional< T > >
 Type trait determining whether type T is cras::optional or not. More...
 
struct  is_string
 Char trait for a C-string or std::string. More...
 
struct  is_string< T, ::std::enable_if_t<::cras::is_c_string< typename std::decay< T >::type >::value > >
 
struct  is_string< T, ::std::enable_if_t<::std::is_same< typename std::decay< T >::type, ::std::string >::value > >
 
class  LoaderROS
 ROS interface for loading/unloading nodelets (internally using nodelet::Loader to do the work). More...
 
class  LogHelper
 This class (reps. its descendants) provides unified access to ROS logging functions, be it ROS_* or NODELET_*. More...
 
class  MemoryLogHelper
 
class  NodeHandle
 
struct  NodeHandleGetParamAdapter
 An adapter that allows getting ROS parameters from a node handle. More...
 
class  NodeHandleWithDiagnostics
 Utils for adding diagnostics to a topic via node handle. More...
 
class  Nodelet
 
class  NodeletAwareTFBuffer
 
class  NodeletBase
 Base template which adds all defined mixins to BaseNodelet class. More...
 
class  NodeletLogHelper
 
class  NodeletManager
 Nodelet manager with customizable instance creation mechanism. More...
 
class  NodeletManagerSharingTfBuffer
 A nodelet manager that can share its TF buffer with cras::NodeletWithSharedTfBuffer nodelets. More...
 
class  NodeletParamHelper
 This mixin allows calling the getParam() helpers. More...
 
struct  NodeletWithDiagnostics
 Nodelet mixin that provides helper functions for running a diagnostics updater. More...
 
struct  NodeletWithSharedTfBuffer
 A nodelet mixin that allows to use a tf2_ros::Buffer provided by the nodelet manager (which should save some computations). If this nodelet has also the StatefulNodelet mixin, the automatically created non-shared buffer is nodelet-aware (you can also pass a NodeletAwareTfBuffer to setBuffer()). That means any TF lookups done via this->getBuffer() will be able to correctly end when the nodelet is being unloaded (which normally hangs: https://github.com/ros/geometry2/issues/381). More...
 
struct  NodeletWithSharedTfBufferInterface
 Public non-template API of NodeletWithSharedTfBuffer. Dynamic_cast a nodelet to this type if you need to access this API publicly. More...
 
class  NodeLogHelper
 
class  NodeParamHelper
 This mixin allows calling the getParam() helpers. More...
 
class  ParamHelper
 This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter values. Each parameter has to be provided a default value, and each parameter read is logged - specified parameters with INFO verbosity level, defaulted parameters with WARN level. There are also lots of template specializations for builtin ROS types or unsigned values which ease the process of reading the parameters correctly. More...
 
struct  ParamToStringFn
 Default function for converting values to string in getParam(Verbose) functions. Uses cras::to_string(). More...
 
class  RateLimiter
 Generic rate-limiter interface. More...
 
class  Resettable
 Interface for resettable nodes and nodelets. More...
 
class  ReverseSemaphore
 A reverse counting semaphore which can wait until its count is zero. Each acquire() increases this count and each release() decreases it. waitZero() is the function that waits until the internal count is zero. The semaphore can be disabled, which means no new acquire() calls will be accepted. This is useful if you plan to quit. More...
 
class  RosconsoleLogHelper
 Log helper relaying all of its work to the same mechanism used by ROS_* logging macros. More...
 
class  RunningStats
 Computation of running average and variance using Welford's algorithm. More...
 
class  SemaphoreGuard
 RAII guard for operations with a semaphore. On creation, the semaphore is acquired, and on destruction, it is released. More...
 
struct  SimpleDurationStatusParam
 Helper struct for easy brace-initialization of DurationStatusParam objects. On supported compilers, you can also use designated braced initialization, i.e. param = {.maxDuration = {10,0}}. Supported is e.g. GCC 8+ in any mode or any compiler in C++20 mode. More...
 
struct  SimpleTopicStatusParamNoHeader
 Helper struct for easy brace-initialization of TopicStatusParam objects. On supported compilers, you can also use designated braced initialization, i.e. param = {.maxRate = 10}. Supported is e.g. GCC 8+ in any mode or any compiler in C++20 mode. More...
 
struct  SimpleTopicStatusParamWithHeader
 Helper struct for easy brace-initialization of TopicStatusParam objects. On supported compilers, you can also use designated braced initialization, i.e. param = {.maxRate = 10}. Supported is e.g. GCC 8+ in any mode or any compiler in C++20 mode. More...
 
class  StatefulNodelet
 A mixin that can tell when a nodelet is being unloaded. More...
 
struct  StatefulNodeletInterface
 A non-templated interface of the mixin that can tell when a nodelet is being unloaded. More...
 
class  ThreadNameUpdatingNodelet
 This mixin allows the nodelet to update the OS name of the thread in which it is currently executing. More...
 
class  ThrottleLimiter
 The (not so clever) algorithm used by topic_tools/throttle node. More...
 
class  TimeJumpResettable
 Interface for resettable nodes and nodelets. Automatic reset on time jumps. More...
 
class  TokenBucketLimiter
 Token bucket rate limiting algorithm. More...
 
class  TopicStatus
 Diagnostic task for topic frequency and timestamp delay (combining FrequencyStatus and TimeStampStatus tasks). More...
 
struct  TopicStatusParams
 Utility class with various predefined topic diagnostic parameters. More...
 
class  TopicStatusParamWithHeader
 A combined parameter defining both rate diagnostics and delay diagnostics (for messages with a header). More...
 
class  WrapperLogHelper
 
struct  XmlRpcValueGetParamAdapter
 
struct  XmlRpcValueTraits
 Type traits for XmlRpcValue. More...
 
struct  XmlRpcValueTraits< bool >
 
struct  XmlRpcValueTraits< char * >
 
struct  XmlRpcValueTraits< char >
 
struct  XmlRpcValueTraits< const char * >
 
struct  XmlRpcValueTraits< double >
 
struct  XmlRpcValueTraits< float >
 
struct  XmlRpcValueTraits< int >
 
struct  XmlRpcValueTraits< long >
 
struct  XmlRpcValueTraits< long double >
 
struct  XmlRpcValueTraits< long long >
 
struct  XmlRpcValueTraits< short >
 
struct  XmlRpcValueTraits< signed char >
 
struct  XmlRpcValueTraits< typename ::XmlRpc::XmlRpcValue::BinaryData >
 
struct  XmlRpcValueTraits< unsigned char >
 
struct  XmlRpcValueTraits< unsigned int >
 
struct  XmlRpcValueTraits< unsigned long >
 
struct  XmlRpcValueTraits< unsigned long long >
 
struct  XmlRpcValueTraits< unsigned short >
 
struct  XmlRpcValueTraits<::std::array< T, N >, typename ::std::enable_if<::cras::XmlRpcValueTraits< T >::xmlRpcType !=::XmlRpc::XmlRpcValue::TypeInvalid >::type >
 
struct  XmlRpcValueTraits<::std::list< T >, typename ::std::enable_if<::cras::XmlRpcValueTraits< T >::xmlRpcType !=::XmlRpc::XmlRpcValue::TypeInvalid >::type >
 
struct  XmlRpcValueTraits<::std::map<::std::string, T >, typename ::std::enable_if<::cras::XmlRpcValueTraits< T >::xmlRpcType !=::XmlRpc::XmlRpcValue::TypeInvalid >::type >
 
struct  XmlRpcValueTraits<::std::set< T >, typename ::std::enable_if<::cras::XmlRpcValueTraits< T >::xmlRpcType !=::XmlRpc::XmlRpcValue::TypeInvalid >::type >
 
struct  XmlRpcValueTraits<::std::string >
 
struct  XmlRpcValueTraits<::std::unordered_map<::std::string, T >, typename ::std::enable_if<::cras::XmlRpcValueTraits< T >::xmlRpcType !=::XmlRpc::XmlRpcValue::TypeInvalid >::type >
 
struct  XmlRpcValueTraits<::std::unordered_set< T >, typename ::std::enable_if<::cras::XmlRpcValueTraits< T >::xmlRpcType !=::XmlRpc::XmlRpcValue::TypeInvalid >::type >
 
struct  XmlRpcValueTraits<::std::vector< T >, typename ::std::enable_if<::cras::XmlRpcValueTraits< T >::xmlRpcType !=::XmlRpc::XmlRpcValue::TypeInvalid >::type >
 
struct  XmlRpcValueTraits<::tm >
 

Typedefs

typedef void *(* allocator_t) (size_t)
 Allocator function that should allocate a buffer of the given size on the caller side and return a pointer to it. More...
 
template<typename M >
using BaseMessage = typename ::ros::ParameterAdapter< M >::Message
 Return the base message type of M (i.e. removes MessageEvent, const, &, shared_ptr etc.). More...
 
typedef ::std::shared_ptr<::cras::BoundParamHelperBoundParamHelperPtr
 
template<typename ResultType , typename ParamServerType >
using check_get_param_types = typename std::enable_if_t< !::cras::is_optional< ResultType >::value &&!::cras::is_c_string< ResultType >::value &&!::cras::is_c_string< ParamServerType >::value >
 This type is a TrueType if the combination of ResultType and ParamServerType is valid. More...
 
typedef ::sensor_msgs::PointCloud2 Cloud
 Shorthand for sensor_msgs::PointCloud2. More...
 
typedef ::sensor_msgs::PointCloud2ConstIterator< float > CloudConstIter
 Const cloud float field iterator. More...
 
typedef ::sensor_msgs::PointCloud2ConstIterator< intCloudIndexConstIter
 Const cloud int field iterator. More...
 
typedef ::sensor_msgs::PointCloud2Iterator< intCloudIndexIter
 Cloud int field iterator. More...
 
typedef ::sensor_msgs::PointCloud2Iterator< float > CloudIter
 Cloud float field iterator. More...
 
typedef ::sensor_msgs::PointCloud2Modifier CloudModifier
 Shorthand for sensor_msgs::PointCloud2Modifier. More...
 
using DurationStatusPtr = ::std::shared_ptr<::cras::DurationStatus >
 
typedef ::cras::impl::GenericCloudConstIterator GenericCloudConstIter
 
typedef ::cras::impl::GenericCloudIterator GenericCloudIter
 GenericCloudIter and GenericCloudConstIter are iterators of fields of types unknown at compile time. More...
 
typedef ::std::shared_ptr<::cras::GetParamAdapterGetParamAdapterPtr
 
template<typename M >
using IsMessageParam = ::ros::message_traits::IsMessage<::cras::BaseMessage< M > >
 Tells whether the given signature designates a ROS message parameters (possibly surrounded by const, &, shared_ptr, MessageEvent etc.). More...
 
typedef ::cras::LogHelper::ConstPtr LogHelperConstPtr
 Const pointer to LogHelper. More...
 
typedef ::cras::LogHelper::Ptr LogHelperPtr
 Pointer to LogHelper. More...
 
typedef ::std::shared_ptr<::cras::ParamHelperParamHelperPtr
 
template<typename Message >
using SimpleTopicStatusParam = ::std::conditional_t<::ros::message_traits::HasHeader< Message >::value, ::cras::SimpleTopicStatusParamWithHeader, ::cras::SimpleTopicStatusParamNoHeader >
 Helper struct for easy brace-initialization of TopicStatusParam objects. More...
 
template<typename Message >
using TopicStatusParam = ::std::conditional_t<::ros::message_traits::HasHeader< Message >::value, ::cras::TopicStatusParamWithHeader, ::cras::FrequencyStatusParam >
 Helper struct for automatic choosing of the correct topic status parameter object based on whether the message type has a header or not. More...
 
template<typename Message >
using TopicStatusPtr = ::std::shared_ptr<::cras::TopicStatus< Message > >
 
template<typename T >
using ToStringFn = ::std::function<::std::string(const T &)>
 Type of function that converts anything to a string. More...
 

Enumerations

enum  chars_format { scientific = 1 << 0, fixed = 1 << 2, hex = 1 << 3, general = fixed | scientific }
 
enum  CloudChannelType { CloudChannelType::POINT, CloudChannelType::DIRECTION, CloudChannelType::SCALAR }
 Type of a pointcloud channel. More...
 
enum  ReplacePosition { ReplacePosition::EVERYWHERE, ReplacePosition::START, ReplacePosition::END }
 Specifies where a replace operation should act. More...
 

Functions

::std::string appendIfNonEmpty (const ::std::string &str, const ::std::string &suffix)
 If str is nonempty, returns str + suffix, otherwise empty string. More...
 
template<class F , class... Args>
auto bind_front (F &&f, Args &&... args)
 
::std::string cleanTypeName (const ::std::string &typeName)
 Remove not-so-nice parts of demangled C++ type names. More...
 
bool contains (const ::std::string &str, char c)
 Check whether str contains character c. More...
 
bool contains (const ::std::string &str, const ::std::string &needle)
 Check whether str contains substring needle. More...
 
bool convert (const ::XmlRpc::XmlRpcValue &x, ::dynamic_reconfigure::Config &v, bool skipNonConvertible, ::std::list<::std::string > *errors)
 
template<typename T , size_t N>
bool convert (const ::XmlRpc::XmlRpcValue &x, ::std::array< T, N > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr)
 
template<typename T >
bool convert (const ::XmlRpc::XmlRpcValue &x, ::std::list< T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr)
 
template<typename T >
bool convert (const ::XmlRpc::XmlRpcValue &x, ::std::map<::std::string, T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr)
 
template<typename T >
bool convert (const ::XmlRpc::XmlRpcValue &x, ::std::set< T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr)
 
template<typename T >
bool convert (const ::XmlRpc::XmlRpcValue &x, ::std::unordered_map<::std::string, T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr)
 
template<typename T >
bool convert (const ::XmlRpc::XmlRpcValue &x, ::std::unordered_set< T > &v, bool skipNonConvertible=false, ::std::list<::std::string > *errors=nullptr)
 
template<typename T >
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)
 Convert XmlRpcValue x to value v. More...
 
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)
 
void copyChannelData (const ::cras::Cloud &in, ::cras::Cloud &out, const ::std::string &fieldName)
 Copy data belonging to the given field from in cloud to out cloud. More...
 
 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)
 Demangle the given mangle C++ type identifier. More...
 
bool endsWith (const ::std::string &str, const ::std::string &suffix)
 Check whether suffix is a suffix of str. More...
 
inline ::std::string format (::std::string format, ::va_list args)
 
inline ::std::string format (::std::string format,...)
 
inline ::std::string format (const char *format, ::va_list args)
 
inline ::std::string format (const char *format,...)
 
double frequency (const ::ros::Rate &rate, bool maxCycleTimeMeansZero=false)
 Return the frequency represented by the given rate. More...
 
double frequency (const ::ros::WallRate &rate, bool maxCycleTimeMeansZero=false)
 Return the frequency represented by the given rate. More...
 
inline ::cras::from_chars_result from_chars (const ::std::string &string, double &value, ::cras::chars_format fmt=::cras::chars_format::general) noexcept
 Convert the given string to its best double representation. The behavior is similar to std::from_chars(), i.e. no leading space of plus sign is allowed. More...
 
inline ::cras::from_chars_result from_chars (const ::std::string &string, float &value, ::cras::chars_format fmt=::cras::chars_format::general) noexcept
 Convert the given string to its best float representation. The behavior is similar to std::from_chars(), i.e. no leading space of plus sign is allowed. More...
 
::cras::from_chars_result from_chars (const char *first, const char *last, double &value, ::cras::chars_format fmt=::cras::chars_format::general) noexcept
 Convert the given string to its best double representation. The behavior is similar to std::from_chars(), i.e. no leading space of plus sign is allowed. More...
 
::cras::from_chars_result from_chars (const char *first, const char *last, float &value, ::cras::chars_format fmt=::cras::chars_format::general) noexcept
 Convert the given string to its best float representation. The behavior is similar to std::from_chars(), i.e. no leading space of plus sign is allowed. More...
 
::sensor_msgs::PointField & getField (::cras::Cloud &cloud, const ::std::string &fieldName)
 Return the sensor_msgs::PointField with the given name. More...
 
const ::sensor_msgs::PointField & getField (const ::cras::Cloud &cloud, const ::std::string &fieldName)
 Return the sensor_msgs::PointField with the given name. More...
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, 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)
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::cras::GetParamAdapter &param, 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)
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}, const ::cras::LogHelper *const logger=nullptr)
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr)
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
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={})
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
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={})
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
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={})
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, 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)
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, 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)
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}, const ::cras::LogHelper *const logger=nullptr)
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr)
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
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={})
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
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={})
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
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={})
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
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={})
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
double getPitch (const ::geometry_msgs::Quaternion &quat)
 Get pitch from the given quaternion. More...
 
double getPitch (const ::tf2::Quaternion &quat)
 Get pitch from the given quaternion. More...
 
double getRoll (const ::geometry_msgs::Quaternion &quat)
 Get roll from the given quaternion. More...
 
double getRoll (const ::tf2::Quaternion &quat)
 Get roll from the given quaternion. More...
 
void getRPY (const ::geometry_msgs::Quaternion &quat, double &roll, double &pitch, double &yaw)
 Get roll, pitch and yaw from the given quaternion. More...
 
void getRPY (const ::tf2::Quaternion &quat, double &roll, double &pitch, double &yaw)
 Get roll, pitch and yaw from the given quaternion. More...
 
std::string getThreadName ()
 Get the OS name of the current thread. More...
 
template<typename T >
inline ::std::string getTypeName ()
 Get a human-readable name of T. More...
 
::std::string getTypeName (const ::std::type_info &typeInfo)
 Get a human-readable name of a type represented by the given typeinfo. More...
 
double getYaw (const ::geometry_msgs::Quaternion &quat)
 Get yaw from the given quaternion. More...
 
double getYaw (const ::tf2::Quaternion &quat)
 Get yaw from the given quaternion. More...
 
bool hasField (const ::cras::Cloud &cloud, const ::std::string &fieldName)
 Return true if the cloud contains a field with the given name. More...
 
bool isNodeletUnloading (const ::nodelet::Nodelet &nodelet)
 Tells whether the nodelet is currently being unloaded (with some pending callbacks still running). More...
 
template<typename T >
bool isSetIntersectionEmpty (const ::std::set< T > &set1, const ::std::set< T > &set2)
 Test whether the two given sets have empty intersection. More...
 
template<typename T >
::std::string join (const T &strings, const ::std::string &delimiter)
 Return a string that is a concatenation of elements of strings delimited by delimiter. More...
 
int8_t logLevelToRosgraphMsgLevel (::ros::console::Level rosLevel)
 Convert the given rosconsole logging level to rosgraph_msgs::Log level constant. More...
 
template<typename T , class... Args>
::boost::shared_ptr< T > make_shared_from_fast_pool (Args &&... args)
 Make a shared instance of an object from Boost fast pool (suitable for e.g. elements of a std::list or single object allocations). More...
 
template<typename T , class... Args>
::boost::shared_ptr< T > make_shared_from_pool (Args &&... args)
 Make a shared instance of an object from Boost pool (suitable for e.g. elements of a std::vector or allocations of multiple objects at once). More...
 
inline ::cras::BoundParamHelperPtr nodeParams (const ::ros::NodeHandle &node, const ::std::string &ns="")
 Returns a param helper structure "bound" to the given node handle, so that it is not needed to specify the node handle in the subsequent getParam() calls. More...
 
::ros::Time nowFallbackToWall ()
 Return current ROS time if it has already been initialized, or current wall time. More...
 
size_t numPoints (const ::cras::Cloud &cloud)
 Return the number of points the given pointcloud contains. More...
 
uint8_t * outputByteBuffer (allocator_t allocator, const std::vector< uint8_t > &bytes)
 Allocate enough bytes using the given allocator and copy the given bytes into the buffer. More...
 
uint8_t * outputByteBuffer (allocator_t allocator, const uint8_t *bytes, size_t length)
 Allocate enough bytes using the given allocator and copy the given bytes into the buffer. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
uint8_t * outputRosMessage (allocator_t allocator, const Message &msg)
 Allocate enough bytes using the given allocator and serialize the given message into it. More...
 
char * outputString (allocator_t allocator, const char *string, size_t length)
 Allocate enough bytes using the given allocator and copy the given string into the buffer (including null termination byte). More...
 
char * outputString (allocator_t allocator, const std::string &string)
 Allocate enough bytes using the given allocator and copy the given string into the buffer (including null termination byte). More...
 
inline ::cras::BoundParamHelperPtr paramsForNodeHandle (const ::ros::NodeHandle &node)
 Returns a param helper structure "bound" to the given node handle, so that it is not needed to specify the node handle in the subsequent getParam() calls. More...
 
double parseDouble (const ::std::string &string)
 Parse the given string to a double. More...
 
double parseDouble (const char *string)
 Parse the given string to a double. More...
 
float parseFloat (const ::std::string &string)
 Parse the given string to a float. More...
 
float parseFloat (const char *string)
 Parse the given string to a float. More...
 
int16_t parseInt16 (const char *string)
 Parse the given string to a 16-bit int. More...
 
int16_t parseInt16 (const std::string &string)
 Parse the given string to a 16-bit int. More...
 
int32_t parseInt32 (const char *string)
 Parse the given string to a 32-bit int. More...
 
int32_t parseInt32 (const std::string &string)
 Parse the given string to a 32-bit int. More...
 
int64_t parseInt64 (const char *string)
 Parse the given string to a 64-bit int. More...
 
int64_t parseInt64 (const std::string &string)
 Parse the given string to a 64-bit int. More...
 
int8_t parseInt8 (const char *string)
 Parse the given string to a 8-bit int. More...
 
int8_t parseInt8 (const std::string &string)
 Parse the given string to a 8-bit int. More...
 
uint16_t parseUInt16 (const char *string)
 Parse the given string to a 16-bit unsigned int. More...
 
uint16_t parseUInt16 (const std::string &string)
 Parse the given string to a 16-bit unsigned int. More...
 
uint32_t parseUInt32 (const char *string)
 Parse the given string to a 32-bit unsigned int. More...
 
uint32_t parseUInt32 (const std::string &string)
 Parse the given string to a 32-bit unsigned int. More...
 
uint64_t parseUInt64 (const char *string)
 Parse the given string to a 64-bit unsigned int. More...
 
uint64_t parseUInt64 (const std::string &string)
 Parse the given string to a 64-bit unsigned int. More...
 
uint8_t parseUInt8 (const char *string)
 Parse the given string to a 8-bit unsigned int. More...
 
uint8_t parseUInt8 (const std::string &string)
 Parse the given string to a 8-bit unsigned int. More...
 
::std::string prependIfNonEmpty (const ::std::string &str, const ::std::string &prefix)
 If str is nonempty, returns prefix + str, otherwise empty string. More...
 
template<typename T , ::std::enable_if_t<!::cras::is_string<::std::decay_t< T >>::value, bool > = true>
inline ::std::string quoteIfStringType (const ::std::string &s, const T &)
 Put s in double quotes if T is a string type (std::string or char*). More...
 
void registerCloudChannelType (const ::std::string &channelPrefix, ::cras::CloudChannelType type)
 Register the given pointcloud channel prefix with the given type. This registration will be used by transformWithChannels() when called without an explicit channel list. More...
 
::ros::Duration remainingTime (const ::ros::Time &query, const ::ros::Duration &timeout)
 Return remaining time to timeout from the query time. More...
 
::ros::Duration remainingTime (const ::ros::Time &query, double timeout)
 Return remaining time to timeout from the query time. More...
 
::std::string removePrefix (const ::std::string &str, const ::std::string &prefix, bool *hadPrefix=nullptr)
 Remove prefix from start of str if it contains it, otherwise return str unchanged. More...
 
::std::string removeSuffix (const ::std::string &str, const ::std::string &suffix, bool *hadSuffix=nullptr)
 Remove suffix from end of str if it contains it, otherwise return str unchanged. More...
 
void replace (::std::string &str, const ::std::string &from, const ::std::string &to, const ::cras::ReplacePosition &where=::cras::ReplacePosition::EVERYWHERE)
 Replace all occurrences of from in str with to. More...
 
::std::string replace (const ::std::string &str, const ::std::string &from, const ::std::string &to, const ::cras::ReplacePosition &where=::cras::ReplacePosition::EVERYWHERE)
 Replace all occurrences of from in str with to. More...
 
::ros::console::Level rosgraphMsgLevelToLogLevel (uint8_t msgLevel)
 Convert the given rosgraph_msgs::Log level constant to rosconsole logging level. More...
 
::ros::Rate safeRate (double frequency)
 Return a rate representing the given frequency. If the frequency is zero or too small, return min/max representable rate. More...
 
::ros::WallRate safeWallRate (double frequency)
 Return a rate representing the given frequency. If the frequency is zero or too small, return min/max representable rate. More...
 
::ros::SteadyTime saturateAdd (const ::ros::SteadyTime &time, const ::ros::WallDuration &duration)
 Add the given duration to the given time, but saturate the result instead of throwing exception on overflow. More...
 
::ros::Time saturateAdd (const ::ros::Time &time, const ::ros::Duration &duration)
 Add the given duration to the given time, but saturate the result instead of throwing exception on overflow. More...
 
::ros::WallTime saturateAdd (const ::ros::WallTime &time, const ::ros::WallDuration &duration)
 Add the given duration to the given time, but saturate the result instead of throwing exception on overflow. More...
 
void setThreadName (const std::string &name)
 Set the OS name of the current thread. More...
 
size_t sizeOfPointField (const ::sensor_msgs::PointField &field)
 Return the size (in bytes) of the data represented by the sensor_msgs::PointField. More...
 
size_t sizeOfPointField (int datatype)
 Return the size (in bytes) of a sensor_msgs::PointField datatype. More...
 
::std::vector<::std::string > split (const ::std::string &str, const ::std::string &delimiter, int maxSplits=-1)
 Split the given string by the given delimiter. More...
 
bool startsWith (const ::std::string &str, const ::std::string &prefix)
 Check whether prefix is a prefix of str. More...
 
void strip (::std::string &s, const char &c=' ')
 Strip c from the beginning and end of the given string (if it is there). More...
 
::std::string strip (const ::std::string &s, const char &c=' ')
 Return a copy of the given string with c removed from its beginning and end (if it was there). More...
 
void stripLeading (::std::string &s, const char &c=' ')
 Strip c from the start of the given string (if there is one). More...
 
::std::string stripLeading (const ::std::string &s, const char &c=' ')
 Return a copy of the given string with c removed from its start (if there is one). More...
 
void stripLeadingSlash (::std::string &s, bool warn=false)
 Strip leading slash from the given string (if there is one). More...
 
::std::string stripLeadingSlash (const ::std::string &s, bool warn=false)
 Return a copy of the given string with leading slash removed (if there is one). More...
 
void stripTrailing (::std::string &s, const char &c=' ')
 Strip c from the end of the given string (if there is one). More...
 
::std::string stripTrailing (const ::std::string &s, const char &c=' ')
 Return a copy of the given string with c removed from its end (if there is one). More...
 
constexpr const char * to_cstring (const ::XmlRpc::XmlRpcValue::Type &value)
 Return a string representation of the XmlRpcValue type. More...
 
inline ::std::string to_string (char *value)
 
template<typename Scalar , int Rows, int Cols, int Options, int MaxRows, int MaxCols>
inline ::std::string to_string (const ::Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols > &value)
 
template<typename Derived , int Dim>
inline ::std::string to_string (const ::Eigen::RotationBase< Derived, Dim > &value)
 
template<typename Scalar , int Dim, int Mode, int Options>
inline ::std::string to_string (const ::Eigen::Transform< Scalar, Dim, Mode, Options > &value)
 
template<typename T , size_t N>
inline ::std::string to_string (const ::std::array< T, N > &value)
 
template<typename K , typename V >
inline ::std::string to_string (const ::std::map< K, V > &value)
 
inline ::std::string to_string (const ::std::string &value)
 
template<typename K , typename V >
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)
 
template<>
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)
 
template<int I>
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)
 
template<typename M , ::std::enable_if_t<::ros::message_traits::IsMessage< M >::value > * = nullptr>
std::string to_string (const M &msg)
 
template<typename T , typename ::std::enable_if_t< ::std::is_same< T, ::ros::Time >::value||::std::is_same< T, ::ros::WallTime >::value||::std::is_same< T, ::ros::SteadyTime >::value||::std::is_same< T, ::ros::Duration >::value||::std::is_same< T, ::ros::WallDuration >::value > * = nullptr>
inline ::std::string to_string (const T &value)
 
template<typename T >
decltype(::std::to_string(::std::declval< T >())) to_string (const T &value)
 Convert the given value to a string representation. More...
 
template<typename T >
decltype(static_cast<::std::string >(::std::declval< T >())) to_string (const T &value)
 Convert the given value to a string representation. More...
 
::Eigen::Isometry3d toEigen (const ::urdf::Pose &pose)
 Convert URDF pose to Eigen transform. More...
 
::Eigen::Quaterniond toEigen (const ::urdf::Rotation &rotation)
 Convert URDF rotation to Eigen quaternion. More...
 
::Eigen::Translation3d toEigen (const ::urdf::Vector3 &position)
 URDF Vector3 to Eigen translation. More...
 
::std::string toLower (const ::std::string &str)
 Convert all characters in the given string to lower case. More...
 
::std::string toUpper (const ::std::string &str)
 Convert all characters in the given string to upper case. More...
 
::urdf::Pose toURDF (const ::Eigen::Isometry3d &pose)
 Convert Eigen isometry to URDF Pose. More...
 
::urdf::Rotation toURDF (const ::Eigen::Quaterniond &rotation)
 Convert Eigen quaternion to URDF Rotation. More...
 
::urdf::Vector3 toURDF (const ::Eigen::Translation3d &translation)
 Convert Eigen translation to URDF Vector3. More...
 
::urdf::Vector3 toURDF (const ::Eigen::Vector3d &vector)
 Convert Eigen vector to URDF Vector3. More...
 
void transformChannel (::sensor_msgs::PointCloud2 &cloud, const ::geometry_msgs::Transform &transform, const ::std::string &channelPrefix, ::cras::CloudChannelType type)
 Transform the given channel in the given cloud using the given transform. More...
 
::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)
 Copy the selected channels from in cloud to out and transform them using the given transform. More...
 
::sensor_msgs::PointCloud2 & transformOnlyXYZ (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf)
 Copy only the XYZ channel from in cloud to out and transform it using the given transform. More...
 
::sensor_msgs::PointCloud2 & transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf)
 Copy in cloud to out and transform channels using the given transform. The list of channels to be transformed consists of the XYZ channel, vp_, normal_ and all channels registered by registerCloudChannelType(). More...
 
::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)
 Copy in cloud to out and transform channels using the given transform. Only the channels passed in channels will be transformed, according to their type. More...
 
::sensor_msgs::PointCloud2 & transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::tf2_ros::Buffer &tfBuffer, const ::std::string &targetFrame)
 Copy in cloud to out and transform channels using the given transform. The list of channels to be transformed consists of the XYZ channel, vp_, normal_ and all channels registered by registerCloudChannelType(). More...
 
::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)
 Copy in cloud to out and transform channels using the given transform. Only the channels passed in channels will be transformed, according to their type. More...
 
void unregisterCloudChannelType (const ::std::string &channelPrefix)
 Unregister a cloud channel type registered earlier with registerCloudChannelType(). More...
 

Variables

 int
 
 LONG_MIN
 
const ParamHelper paramHelper (::std::make_shared<::cras::NodeLogHelper >())
 

Typedef Documentation

◆ allocator_t

typedef void*(* cras::allocator_t) (size_t)

Allocator function that should allocate a buffer of the given size on the caller side and return a pointer to it.

This is used throughout the C API to ease returning strings and byte buffers of dynamic size to the caller. Instead of taking a writable char* argument or returning a new-allocated const char*, the function takes the allocator as the argument. When it is about to return to the caller, it uses the allocator to get a caller-side-managed buffer of the correct size and writes the string/byte buffer to this buffer.

cras_py_common provides the BytesAllocator and StringAllocator classes that can be passed as this allocator argument. Once the ctypes function call finishes, the caller can access allocator.value to get the string or buffer returned by the function.

Definition at line 36 of file c_api.h.

◆ BaseMessage

template<typename M >
using cras::BaseMessage = typedef typename ::ros::ParameterAdapter<M>::Message

Return the base message type of M (i.e. removes MessageEvent, const, &, shared_ptr etc.).

Definition at line 19 of file message_utils.hpp.

◆ BoundParamHelperPtr

typedef ::std::shared_ptr<::cras::BoundParamHelper> cras::BoundParamHelperPtr

Definition at line 24 of file bound_param_helper.hpp.

◆ check_get_param_types

template<typename ResultType , typename ParamServerType >
using cras::check_get_param_types = typedef typename std::enable_if_t< !::cras::is_optional<ResultType>::value && !::cras::is_c_string<ResultType>::value && !::cras::is_c_string<ParamServerType>::value >

This type is a TrueType if the combination of ResultType and ParamServerType is valid.

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.

Definition at line 67 of file param_utils.hpp.

◆ Cloud

typedef ::sensor_msgs::PointCloud2 cras::Cloud

Shorthand for sensor_msgs::PointCloud2.

Definition at line 23 of file cloud.hpp.

◆ CloudConstIter

Const cloud float field iterator.

Definition at line 32 of file cloud.hpp.

◆ CloudIndexConstIter

Const cloud int field iterator.

Definition at line 35 of file cloud.hpp.

◆ CloudIndexIter

Cloud int field iterator.

Definition at line 29 of file cloud.hpp.

◆ CloudIter

Cloud float field iterator.

Definition at line 26 of file cloud.hpp.

◆ CloudModifier

Shorthand for sensor_msgs::PointCloud2Modifier.

Definition at line 38 of file cloud.hpp.

◆ DurationStatusPtr

using cras::DurationStatusPtr = typedef ::std::shared_ptr<::cras::DurationStatus>

Definition at line 140 of file duration_status.h.

◆ GenericCloudConstIter

typedef ::cras::impl::GenericCloudConstIterator cras::GenericCloudConstIter

Definition at line 61 of file cloud.hpp.

◆ GenericCloudIter

typedef ::cras::impl::GenericCloudIterator cras::GenericCloudIter

GenericCloudIter and GenericCloudConstIter are iterators of fields of types unknown at compile time.

The iterators allow you to dereference them into an unsigned char, which doesn't however need to be the actual data, as they may span multiple bytes.

It adds function rawData() which returns a pointer to the current position in the uchar data stream. You can use reinterpret_cast to transform the data into some desired type and get or set the value. Any kind of data safety is on you.

Another provided function is dataAs<Type>() which returns the current iterator position as a pointer to data of the requested type. This function does a basic check that the requested data type has the same size as the type of the iterated field.

The non-const iterator also provides method copyData() which can copy the field data from another generic iterator. This can be used to copy fields of types which are not known at compile time.

Definition at line 58 of file cloud.hpp.

◆ GetParamAdapterPtr

typedef ::std::shared_ptr<::cras::GetParamAdapter> cras::GetParamAdapterPtr

Definition at line 57 of file get_param_adapter.hpp.

◆ IsMessageParam

template<typename M >
using cras::IsMessageParam = typedef ::ros::message_traits::IsMessage<::cras::BaseMessage<M> >

Tells whether the given signature designates a ROS message parameters (possibly surrounded by const, &, shared_ptr, MessageEvent etc.).

Definition at line 24 of file message_utils.hpp.

◆ LogHelperConstPtr

Const pointer to LogHelper.

Definition at line 203 of file log_utils.h.

◆ LogHelperPtr

Pointer to LogHelper.

Definition at line 202 of file log_utils.h.

◆ ParamHelperPtr

typedef ::std::shared_ptr<::cras::ParamHelper> cras::ParamHelperPtr

Definition at line 266 of file param_utils/param_helper.hpp.

◆ SimpleTopicStatusParam

template<typename Message >
using cras::SimpleTopicStatusParam = typedef ::std::conditional_t<::ros::message_traits::HasHeader<Message>::value, ::cras::SimpleTopicStatusParamWithHeader, ::cras::SimpleTopicStatusParamNoHeader>

Helper struct for easy brace-initialization of TopicStatusParam objects.

Template Parameters
MessageType of the message for which parameters are constructed.
Note
This typedef automatically chooses WithHeader or NoHeader variant of the struct based on the type of the message.

Definition at line 80 of file topic_status_param.hpp.

◆ TopicStatusParam

template<typename Message >
using cras::TopicStatusParam = typedef ::std::conditional_t<::ros::message_traits::HasHeader<Message>::value, ::cras::TopicStatusParamWithHeader, ::cras::FrequencyStatusParam>

Helper struct for automatic choosing of the correct topic status parameter object based on whether the message type has a header or not.

Template Parameters
MessageType of the message for which parameters are constructed.
Note
This typedef automatically chooses either cras::FrequencyStatusParam or cras::TopicStatusParamWithHeader based on the type of the message.

Definition at line 280 of file topic_status_param.hpp.

◆ TopicStatusPtr

template<typename Message >
using cras::TopicStatusPtr = typedef ::std::shared_ptr<::cras::TopicStatus<Message> >

Definition at line 250 of file topic_status.hpp.

◆ ToStringFn

template<typename T >
using cras::ToStringFn = typedef ::std::function<::std::string(const T&)>

Type of function that converts anything to a string.

Definition at line 339 of file string_utils.hpp.

Enumeration Type Documentation

◆ chars_format

Enumerator
scientific 
fixed 
hex 
general 

Definition at line 17 of file from_chars.h.

◆ CloudChannelType

Type of a pointcloud channel.

Enumerator
POINT 

A 3D point (if transformed, both translation and rotation is applied).

DIRECTION 

A 3D vector/direction (if transformed, only rotation is applied).

SCALAR 

A scalar value (not affected by transforms).

Definition at line 25 of file tf2_sensor_msgs.h.

◆ ReplacePosition

enum cras::ReplacePosition
strong

Specifies where a replace operation should act.

Enumerator
EVERYWHERE 

Act in the whole string.

START 

Act only on the beginning of the string.

END 

Act only on the end of the string.

Definition at line 143 of file string_utils.hpp.

Function Documentation

◆ appendIfNonEmpty()

::std::string cras::appendIfNonEmpty ( const ::std::string &  str,
const ::std::string &  suffix 
)

If str is nonempty, returns str + suffix, otherwise empty string.

Parameters
[in]strThe main string.
[in]suffixThe string's suffix.
Returns
The possibly suffixed string.

◆ bind_front()

template<class F , class... Args>
auto cras::bind_front ( F &&  f,
Args &&...  args 
)

Definition at line 48 of file functional.hpp.

◆ cleanTypeName()

::std::string cras::cleanTypeName ( const ::std::string &  typeName)

Remove not-so-nice parts of demangled C++ type names.

Parameters
[in]typeNameName of a demangled C++ type.
Returns
A better name.

◆ contains() [1/2]

bool cras::contains ( const ::std::string &  str,
char  c 
)

Check whether str contains character c.

Parameters
[in]strThe string to search in.
[in]cThe character to search.
Returns
Whether str contains character c.

◆ contains() [2/2]

bool cras::contains ( const ::std::string &  str,
const ::std::string &  needle 
)

Check whether str contains substring needle.

Parameters
[in]strThe string to search in.
[in]needleThe substring to search.
Returns
Whether str contains substring needle.

◆ convert() [1/13]

bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::dynamic_reconfigure::Config &  v,
bool  skipNonConvertible,
::std::list<::std::string > *  errors 
)
inline

Definition at line 309 of file xmlrpc_value_utils.hpp.

◆ convert() [2/13]

template<typename T , size_t N>
bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::std::array< T, N > &  v,
bool  skipNonConvertible = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

Definition at line 258 of file xmlrpc_value_utils.hpp.

◆ convert() [3/13]

template<typename T >
bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::std::list< T > &  v,
bool  skipNonConvertible = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

◆ convert() [4/13]

template<typename T >
bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::std::map<::std::string, T > &  v,
bool  skipNonConvertible = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

◆ convert() [5/13]

template<typename T >
bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::std::set< T > &  v,
bool  skipNonConvertible = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

◆ convert() [6/13]

template<typename T >
bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::std::unordered_map<::std::string, T > &  v,
bool  skipNonConvertible = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

◆ convert() [7/13]

template<typename T >
bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::std::unordered_set< T > &  v,
bool  skipNonConvertible = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

◆ convert() [8/13]

template<typename T >
bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::std::vector< T > &  v,
bool  skipNonConvertible = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

◆ convert() [9/13]

bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
::XmlRpc::XmlRpcValue v,
bool  = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

Convert XmlRpcValue x to value v.

Parameters
[in]xThe XmlRpcValue to convert.
[out]vThe value to convert to.
[in,out]errorsIf non-null, any conversion error messages will be stored here.
Returns
True if the conversion succeeded. If skipNonConvertible is true, conversion will succeed if at least one contained value succeeded converting (if converting to a container type).

Definition at line 53 of file xmlrpc_value_utils.hpp.

◆ convert() [10/13]

bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
bool &  v,
bool  = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

Definition at line 61 of file xmlrpc_value_utils.hpp.

◆ convert() [11/13]

bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
double &  v,
bool  = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

Definition at line 133 of file xmlrpc_value_utils.hpp.

◆ convert() [12/13]

bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
int v,
bool  = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

Definition at line 87 of file xmlrpc_value_utils.hpp.

◆ convert() [13/13]

bool cras::convert ( const ::XmlRpc::XmlRpcValue x,
std::string &  v,
bool  = false,
::std::list<::std::string > *  errors = nullptr 
)
inline

Definition at line 179 of file xmlrpc_value_utils.hpp.

◆ copyChannelData()

void cras::copyChannelData ( const ::cras::Cloud in,
::cras::Cloud out,
const ::std::string &  fieldName 
)

Copy data belonging to the given field from in cloud to out cloud.

Parameters
[in]inThe input cloud.
[out]outThe ouptut cloud. It has to be resized to contain at least that many points as the input cloud. It also has to have the given field present already.
[in]fieldNameName of the field whose data should be copied.
Exceptions
std::runtime_errorIf the output cloud is smaller (in nr. of points) than the input cloud.
std::runtime_errorIf the given field doesn't exist in either of the clouds.

◆ DEFINE_CONVERTING_GET_PARAM() [1/4]

cras::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() [2/4]

cras::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() [3/4]

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;}   
)

Definition at line 39 of file geometry_msgs.hpp.

◆ DEFINE_CONVERTING_GET_PARAM() [4/4]

cras::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_INTEGRAL_CONVERT() [1/3]

LONG_MAX cras::DEFINE_INTEGRAL_CONVERT ( long long  ,
int  ,
LONG_LONG_MIN  ,
LONG_LONG_MAX   
)

◆ DEFINE_INTEGRAL_CONVERT() [2/3]

cras::DEFINE_INTEGRAL_CONVERT ( short  ,
int  ,
SHRT_MIN  ,
SHRT_MAX   
)

◆ DEFINE_INTEGRAL_CONVERT() [3/3]

LONG_MAX USHRT_MAX cras::DEFINE_INTEGRAL_CONVERT ( unsigned long  ,
int  ,
,
ULONG_MAX   
)

◆ demangle()

::std::string cras::demangle ( const ::std::string &  mangled)

Demangle the given mangle C++ type identifier.

Parameters
[in]mangledThe mangled name.
Returns
The demangled name if demangling succeeded. Otherwise, return mangled.

◆ endsWith()

bool cras::endsWith ( const ::std::string &  str,
const ::std::string &  suffix 
)

Check whether suffix is a suffix of str.

Parameters
[in]strThe string to be searched in.
[in]suffixThe string to be found in str.
Returns
Whether suffix is a suffix of str.

◆ format() [1/4]

inline ::std::string cras::format ( ::std::string  format,
::va_list  args 
)

printf-like support working with std::string and automatically managing memory.

Parameters
[in]formatThe printf-like format string.
[in]argsArguments of the format string.
Returns
The formatted string.

Definition at line 285 of file string_utils.hpp.

◆ format() [2/4]

inline ::std::string cras::format ( ::std::string  format,
  ... 
)

printf-like support working with std::string and automatically managing memory.

Parameters
[in]formatThe printf-like format string.
[in]...Arguments of the format string.
Returns
The formatted string.

Definition at line 270 of file string_utils.hpp.

◆ format() [3/4]

inline ::std::string cras::format ( const char *  format,
::va_list  args 
)

printf-like support working with std::string and automatically managing memory.

Parameters
[in]formatThe printf-like format string.
[in]argsArguments of the format string.
Returns
The formatted string.

Definition at line 223 of file string_utils.hpp.

◆ format() [4/4]

inline ::std::string cras::format ( const char *  format,
  ... 
)

printf-like support working with std::string and automatically managing memory.

Parameters
[in]formatThe printf-like format string.
[in]...Arguments of the format string.
Returns
The formatted string.

Definition at line 255 of file string_utils.hpp.

◆ frequency() [1/2]

double cras::frequency ( const ::ros::Rate rate,
bool  maxCycleTimeMeansZero = false 
)

Return the frequency represented by the given rate.

Parameters
[in]rateThe rate to convert.
[in]maxCycleTimeMeansZeroIf true, return 0 frequency in case the rate's cycle time is the maximum duration.
Returns
The frequency.

◆ frequency() [2/2]

double cras::frequency ( const ::ros::WallRate rate,
bool  maxCycleTimeMeansZero = false 
)

Return the frequency represented by the given rate.

Parameters
[in]rateThe rate to convert.
[in]maxCycleTimeMeansZeroIf true, return 0 frequency in case the rate's cycle time is the maximum duration.
Returns
The frequency.

◆ from_chars() [1/4]

inline ::cras::from_chars_result cras::from_chars ( const ::std::string &  string,
double &  value,
::cras::chars_format  fmt = ::cras::chars_format::general 
)
noexcept

Convert the given string to its best double representation. The behavior is similar to std::from_chars(), i.e. no leading space of plus sign is allowed.

Parameters
[in]stringThe string to convert.
[out]valueThe parsed value (valid only if parsing succeeded, i.e. ec in the result is 0).
[in]fmtBitmask of cras::chars_format values that specify the format rules with which the value should be interpreted. Not all formats have to be supported.
Returns
Struct containing the error code ec - 0 on success, std::errc::invalid_argument if no number could be parsed, and std::errc::result_out_of_range if a numeric value was parsed but did not fit into a double. It is implementation specific, whether result_out_of_range or 0/inf will be returned for too small/large values. ptr points to the first character that was not parsed as a part of the numeric value.

Definition at line 93 of file from_chars.h.

◆ from_chars() [2/4]

inline ::cras::from_chars_result cras::from_chars ( const ::std::string &  string,
float &  value,
::cras::chars_format  fmt = ::cras::chars_format::general 
)
noexcept

Convert the given string to its best float representation. The behavior is similar to std::from_chars(), i.e. no leading space of plus sign is allowed.

Parameters
[in]stringThe string to convert.
[out]valueThe parsed value (valid only if parsing succeeded, i.e. ec in the result is 0).
[in]fmtBitmask of cras::chars_format values that specify the format rules with which the value should be interpreted. Not all formats have to be supported.
Returns
Struct containing the error code ec - 0 on success, std::errc::invalid_argument if no number could be parsed, and std::errc::result_out_of_range if a numeric value was parsed but did not fit into a float. It is implementation specific, whether result_out_of_range or 0/inf will be returned for too small/large values. ptr points to the first character that was not parsed as a part of the numeric value.

Definition at line 75 of file from_chars.h.

◆ from_chars() [3/4]

::cras::from_chars_result cras::from_chars ( const char *  first,
const char *  last,
double &  value,
::cras::chars_format  fmt = ::cras::chars_format::general 
)
noexcept

Convert the given string to its best double representation. The behavior is similar to std::from_chars(), i.e. no leading space of plus sign is allowed.

Parameters
[in]firstPointer to first char of the string.
[in]lastPointer to last char of the string.
[out]valueThe parsed value (valid only if parsing succeeded, i.e. ec in the result is 0).
[in]fmtBitmask of cras::chars_format values that specify the format rules with which the value should be interpreted. Not all formats have to be supported.
Returns
Struct containing the error code ec - 0 on success, std::errc::invalid_argument if no number could be parsed, and std::errc::result_out_of_range if a numeric value was parsed but did not fit into a double. It is implementation specific, whether result_out_of_range or 0/inf will be returned for too small/large values. ptr points to the first character that was not parsed as a part of the numeric value.

◆ from_chars() [4/4]

::cras::from_chars_result cras::from_chars ( const char *  first,
const char *  last,
float &  value,
::cras::chars_format  fmt = ::cras::chars_format::general 
)
noexcept

Convert the given string to its best float representation. The behavior is similar to std::from_chars(), i.e. no leading space of plus sign is allowed.

Parameters
[in]firstPointer to first char of the string.
[in]lastPointer to last char of the string.
[out]valueThe parsed value (valid only if parsing succeeded, i.e. ec in the result is 0).
[in]fmtBitmask of cras::chars_format values that specify the format rules with which the value should be interpreted. Not all formats have to be supported.
Returns
Struct containing the error code ec - 0 on success, std::errc::invalid_argument if no number could be parsed, and std::errc::result_out_of_range if a numeric value was parsed but did not fit into a float. It is implementation specific, whether result_out_of_range or 0/inf will be returned for too small/large values. ptr points to the first character that was not parsed as a part of the numeric value.

◆ getField() [1/2]

::sensor_msgs::PointField& cras::getField ( ::cras::Cloud cloud,
const ::std::string &  fieldName 
)

Return the sensor_msgs::PointField with the given name.

Parameters
[in]cloudCloud to extract the field from.
[in]fieldNameName of the field.
Returns
Reference to the field.
Exceptions
std::runtime_errorif the field doesn't exist.

◆ getField() [2/2]

const ::sensor_msgs::PointField& cras::getField ( const ::cras::Cloud cloud,
const ::std::string &  fieldName 
)

Return the sensor_msgs::PointField with the given name.

Parameters
[in]cloudCloud to extract the field from.
[in]fieldNameName of the field.
Returns
Reference to the field.
Exceptions
std::runtime_errorif the field doesn't exist.

◆ getParam() [1/8]

inline ::std::string cras::getParam ( const ::cras::GetParamAdapter param,
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 
)

Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified).

This is a variant allowing use of C-string instead of std::string.

Parameters
[in]paramThe parameter adapter from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
[in]loggerThe LogHelper used for printing messages. If nullptr, no messages are printed.
Returns
The loaded parameter value.

Definition at line 441 of file param_utils.hpp.

◆ getParam() [2/8]

template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType cras::getParam ( const ::cras::GetParamAdapter param,
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

Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified).

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.
Parameters
[in]paramThe parameter adapter from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
[in]loggerThe LogHelper used for printing messages. If nullptr, no messages are printed.
Returns
The loaded parameter value.

Definition at line 335 of file param_utils.hpp.

◆ getParam() [3/8]

inline ::std::string cras::getParam ( const ::cras::GetParamAdapter param,
const ::std::string &  name,
const char *  defaultValue,
const ::std::string &  unit = "",
const ::cras::GetParamOptions<::std::string > &  options = {},
const ::cras::LogHelper *const  logger = nullptr 
)

Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).

This is a variant allowing use of C-string instead of std::string.

Parameters
[in]paramThe parameter adapter from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
[in]loggerThe LogHelper used for printing messages. If nullptr, no messages are printed.
Returns
The loaded parameter value.

Definition at line 463 of file param_utils.hpp.

◆ getParam() [4/8]

template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType cras::getParam ( const ::cras::GetParamAdapter param,
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

Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.
Parameters
[in]paramThe parameter adapter from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
[in]loggerThe LogHelper used for printing messages. If nullptr, no messages are printed.
Returns
The loaded parameter value.

Definition at line 365 of file param_utils.hpp.

◆ getParam() [5/8]

inline ::std::string cras::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 = {} 
)

Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified).

This is a variant allowing use of C-string instead of std::string.

Parameters
[in]nodeThe node handle from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
Returns
The loaded parameter value.

Definition at line 210 of file node_utils.hpp.

◆ getParam() [6/8]

template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType cras::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

Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified).

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.
Parameters
[in]nodeThe node handle from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
Returns
The loaded parameter value.

Definition at line 110 of file node_utils.hpp.

◆ getParam() [7/8]

inline ::std::string cras::getParam ( const ::ros::NodeHandle node,
const ::std::string &  name,
const char *  defaultValue,
const ::std::string &  unit = "",
const ::cras::GetParamOptions< std::string > &  options = {} 
)

Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).

This is a variant allowing use of C-string instead of std::string.

Parameters
[in]nodeThe node handle from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
Returns
The loaded parameter value.

Definition at line 232 of file node_utils.hpp.

◆ getParam() [8/8]

template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType cras::getParam ( const ::ros::NodeHandle node,
const ::std::string &  name,
const ResultType &  defaultValue = ResultType(),
const ::std::string &  unit = "",
const ::cras::GetParamOptions< ResultType, ParamServerType > &  options = {} 
)
inline

Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.
Parameters
[in]nodeThe node handle from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
Returns
The loaded parameter value.

Definition at line 139 of file node_utils.hpp.

◆ getParamVerbose() [1/8]

inline ::cras::GetParamResult<::std::string> cras::getParamVerbose ( const ::cras::GetParamAdapter param,
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 
)

Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified).

This is a variant allowing use of C-string instead of std::string.

Parameters
[in]paramThe parameter adapter from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
[in]loggerThe LogHelper used for printing messages. If nullptr, no messages are printed.
Returns
A wrapper containing the loaded parameter value and details about the function execution.

Definition at line 392 of file param_utils.hpp.

◆ getParamVerbose() [2/8]

template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult<ResultType> cras::getParamVerbose ( const ::cras::GetParamAdapter param,
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 
)

Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified).

Overloads defining conversion to various types can be defined in several forms. You can either overload cras::convert() that converts the XmlRpcValue to an intermediate value, or you can make the intermediate value autoconvertible to the result type, or you can create a specialization of DefaultToResultFn and DefaultParamServerType, or you can overload getParamVerbose() itself.

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.
Parameters
[in]paramThe parameter adapter from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
[in]loggerThe LogHelper used for printing messages. If nullptr, no messages are printed.
Returns
A wrapper containing the loaded parameter value and details about the function execution.

Definition at line 95 of file param_utils.hpp.

◆ getParamVerbose() [3/8]

inline ::cras::GetParamResult<::std::string> cras::getParamVerbose ( const ::cras::GetParamAdapter param,
const ::std::string &  name,
const char *  defaultValue,
const ::std::string &  unit = "",
const ::cras::GetParamOptions<::std::string > &  options = {},
const ::cras::LogHelper *const  logger = nullptr 
)

Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).

This is a variant allowing use of C-string instead of std::string.

Parameters
[in]paramThe parameter adapter from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
[in]loggerThe LogHelper used for printing messages. If nullptr, no messages are printed.
Returns
A wrapper containing the loaded parameter value and details about the function execution.

Definition at line 417 of file param_utils.hpp.

◆ getParamVerbose() [4/8]

template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult<ResultType> cras::getParamVerbose ( const ::cras::GetParamAdapter param,
const ::std::string &  name,
const ResultType &  defaultValue = ResultType(),
const ::std::string &  unit = "",
const ::cras::GetParamOptions< ResultType, ParamServerType > &  options = {},
const ::cras::LogHelper *const  logger = nullptr 
)

Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.
Parameters
[in]paramThe parameter adapter from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
[in]loggerThe LogHelper used for printing messages. If nullptr, no messages are printed.
Returns
A wrapper containing the loaded parameter value and details about the function execution.

Definition at line 304 of file param_utils.hpp.

◆ getParamVerbose() [5/8]

GetParamResult<::std::string> cras::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 = {} 
)
inline

Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified).

This is a variant allowing use of C-string instead of std::string.

Parameters
[in]nodeThe node handle from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
Returns
A wrapper containing the loaded parameter value and details about the function execution.

Definition at line 165 of file node_utils.hpp.

◆ getParamVerbose() [6/8]

template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
GetParamResult<ResultType> cras::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 = {} 
)
inline

Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified).

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.
Parameters
[in]nodeThe node handle from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
Returns
A wrapper containing the loaded parameter value and details about the function execution.

Definition at line 51 of file node_utils.hpp.

◆ getParamVerbose() [7/8]

GetParamResult<::std::string> cras::getParamVerbose ( const ::ros::NodeHandle node,
const ::std::string &  name,
const char *  defaultValue,
const ::std::string &  unit = "",
const ::cras::GetParamOptions<::std::string > &  options = {} 
)
inline

Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).

This is a variant allowing use of C-string instead of std::string.

Parameters
[in]nodeThe node handle from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
Returns
A wrapper containing the loaded parameter value and details about the function execution.

Definition at line 187 of file node_utils.hpp.

◆ getParamVerbose() [8/8]

template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
GetParamResult<ResultType> cras::getParamVerbose ( const ::ros::NodeHandle node,
const ::std::string &  name,
const ResultType &  defaultValue = ResultType(),
const ::std::string &  unit = "",
const ::cras::GetParamOptions< ResultType, ParamServerType > &  options = {} 
)
inline

Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).

Template Parameters
ResultTypeParam type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast).
ParamServerTypeIntermediate type to which the XmlRpcValue read from parameter server is converted. The conversion is done using options.toParam function (which defaults to cras::convert). Most overloads of cras::convert are in xmlrpc_value_utils.hpp, but you can add your own.
Parameters
[in]nodeThe node handle from which parameters are read.
[in]nameName of the parameter.
[in]defaultValueThe default value to use.
[in]unitOptional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative.
[in]optionsOptions specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false}.
Returns
A wrapper containing the loaded parameter value and details about the function execution.

Definition at line 80 of file node_utils.hpp.

◆ getPitch() [1/2]

double cras::getPitch ( const ::geometry_msgs::Quaternion &  quat)

Get pitch from the given quaternion.

Parameters
[in]quatThe quaternion to convert.
Returns
Pitch in radians.

◆ getPitch() [2/2]

double cras::getPitch ( const ::tf2::Quaternion quat)

Get pitch from the given quaternion.

Parameters
[in]quatThe quaternion to convert.
Returns
Pitch in radians.

◆ getRoll() [1/2]

double cras::getRoll ( const ::geometry_msgs::Quaternion &  quat)

Get roll from the given quaternion.

Parameters
[in]quatThe quaternion to convert.
Returns
Roll in radians.

◆ getRoll() [2/2]

double cras::getRoll ( const ::tf2::Quaternion quat)

Get roll from the given quaternion.

Parameters
[in]quatThe quaternion to convert.
Returns
Roll in radians.

◆ getRPY() [1/2]

void cras::getRPY ( const ::geometry_msgs::Quaternion &  quat,
double &  roll,
double &  pitch,
double &  yaw 
)

Get roll, pitch and yaw from the given quaternion.

Parameters
[in]quatThe quaternion to convert.
[out]rollRoll in radians.
[out]pitchPitch in radians.
[out]yawYaw in radians.

◆ getRPY() [2/2]

void cras::getRPY ( const ::tf2::Quaternion quat,
double &  roll,
double &  pitch,
double &  yaw 
)

Get roll, pitch and yaw from the given quaternion.

Parameters
[in]quatThe quaternion to convert.
[out]rollRoll in radians.
[out]pitchPitch in radians.
[out]yawYaw in radians.

◆ getThreadName()

std::string cras::getThreadName ( )

Get the OS name of the current thread.

Returns
Name of the thread (up to 15 characters).
Note
This function is actually pretty fast. It can be called more than 1 million times per second.

◆ getTypeName() [1/2]

template<typename T >
inline ::std::string cras::getTypeName ( )

Get a human-readable name of T.

Template Parameters
TType to get info about.
Returns
Human-readable name.

Definition at line 41 of file type_utils.hpp.

◆ getTypeName() [2/2]

::std::string cras::getTypeName ( const ::std::type_info &  typeInfo)

Get a human-readable name of a type represented by the given typeinfo.

Parameters
[in]typeInfoInfo about the type.
Returns
Human-readable name.

◆ getYaw() [1/2]

double cras::getYaw ( const ::geometry_msgs::Quaternion &  quat)

Get yaw from the given quaternion.

Parameters
[in]quatThe quaternion to convert.
Returns
Yaw in radians.

◆ getYaw() [2/2]

double cras::getYaw ( const ::tf2::Quaternion quat)

Get yaw from the given quaternion.

Parameters
[in]quatThe quaternion to convert.
Returns
Yaw in radians.

◆ hasField()

bool cras::hasField ( const ::cras::Cloud cloud,
const ::std::string &  fieldName 
)

Return true if the cloud contains a field with the given name.

Parameters
[in]cloudThe cloud to search.
[in]fieldNameName of the field.
Returns
Whether the field is there or not.

◆ isNodeletUnloading()

bool cras::isNodeletUnloading ( const ::nodelet::Nodelet nodelet)

Tells whether the nodelet is currently being unloaded (with some pending callbacks still running).

Parameters
[in]nodeletThe nodelet to check.
Returns
Whether the nodelet is being unloaded.
Note
Be sure to not call this function after the nodelet has finished unloading and its destructor has finished.

◆ isSetIntersectionEmpty()

template<typename T >
bool cras::isSetIntersectionEmpty ( const ::std::set< T > &  set1,
const ::std::set< T > &  set2 
)

Test whether the two given sets have empty intersection.

Template Parameters
TType of the elements in the sets.
Parameters
[in]set1First set to test.
[in]set2Second set to test.
Returns
Whether the intersection of set1 and set2 is empty.

Definition at line 26 of file set_utils.hpp.

◆ join()

template<typename T >
::std::string cras::join ( const T &  strings,
const ::std::string &  delimiter 
)

Return a string that is a concatenation of elements of strings delimited by delimiter.

Template Parameters
TAn iterable type (must support size() and foreach).
Parameters
[in]stringsThe elements to put into a string.
[in]delimiterDelimiter put between elements.
Returns
The concatenated string.

Definition at line 486 of file string_utils.hpp.

◆ logLevelToRosgraphMsgLevel()

int8_t cras::logLevelToRosgraphMsgLevel ( ::ros::console::Level  rosLevel)

Convert the given rosconsole logging level to rosgraph_msgs::Log level constant.

Parameters
[in]rosLevelThe rosconsole logging level.
Returns
The rosgraph_msgs::Log level constant.

◆ make_shared_from_fast_pool()

template<typename T , class... Args>
::boost::shared_ptr<T> cras::make_shared_from_fast_pool ( Args &&...  args)

Make a shared instance of an object from Boost fast pool (suitable for e.g. elements of a std::list or single object allocations).

Template Parameters
TType of the object to allocate.
ArgsConstructor argument types.
Parameters
[in]argsConstructor arguments.
Returns
The shared instance.
Note
Usage in ROS code: msg = cras::make_shared_from_fast_pool<sensor_msgs::PointCloud2>();

Definition at line 32 of file pool_allocator.hpp.

◆ make_shared_from_pool()

template<typename T , class... Args>
::boost::shared_ptr<T> cras::make_shared_from_pool ( Args &&...  args)

Make a shared instance of an object from Boost pool (suitable for e.g. elements of a std::vector or allocations of multiple objects at once).

Template Parameters
TType of the object to allocate.
ArgsConstructor argument types.
Parameters
[in]argsConstructor arguments.
Returns
The shared instance.
Note
Usage in ROS code: msg = cras::make_shared_from_pool<sensor_msgs::PointCloud2>();

Definition at line 49 of file pool_allocator.hpp.

◆ nodeParams()

inline ::cras::BoundParamHelperPtr cras::nodeParams ( const ::ros::NodeHandle node,
const ::std::string &  ns = "" 
)

Returns a param helper structure "bound" to the given node handle, so that it is not needed to specify the node handle in the subsequent getParam() calls.

Parameters
[in]nodeThe node to bind to.
[in]nsIf nonempty, returns just the parameters in the given namespace.
Returns
The bound param helper.

Definition at line 248 of file node_utils.hpp.

◆ nowFallbackToWall()

::ros::Time cras::nowFallbackToWall ( )

Return current ROS time if it has already been initialized, or current wall time.

Returns
Current time.

◆ numPoints()

size_t cras::numPoints ( const ::cras::Cloud cloud)
inline

Return the number of points the given pointcloud contains.

Parameters
[in]cloudThe cloud to examine.
Returns
The number of points.

Definition at line 68 of file cloud.hpp.

◆ outputByteBuffer() [1/2]

uint8_t* cras::outputByteBuffer ( allocator_t  allocator,
const std::vector< uint8_t > &  bytes 
)

Allocate enough bytes using the given allocator and copy the given bytes into the buffer.

Parameters
[in]allocatorThe allocator to use.
[in]bytesThe bytes to copy into the allocated buffer.
Returns
Pointer to the allocated buffer.

◆ outputByteBuffer() [2/2]

uint8_t* cras::outputByteBuffer ( allocator_t  allocator,
const uint8_t *  bytes,
size_t  length 
)

Allocate enough bytes using the given allocator and copy the given bytes into the buffer.

Parameters
[in]allocatorThe allocator to use.
[in]bytesThe bytes to copy into the allocated buffer.
[in]lengthLength of bytes.
Returns
Pointer to the allocated buffer.

◆ outputRosMessage()

template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
uint8_t* cras::outputRosMessage ( allocator_t  allocator,
const Message &  msg 
)

Allocate enough bytes using the given allocator and serialize the given message into it.

Parameters
[in]allocatorThe allocator to use.
[in]msgThe message to serialize.
Returns
Pointer to the allocated buffer.

Definition at line 81 of file c_api.h.

◆ outputString() [1/2]

char* cras::outputString ( allocator_t  allocator,
const char *  string,
size_t  length 
)

Allocate enough bytes using the given allocator and copy the given string into the buffer (including null termination byte).

Parameters
[in]allocatorThe allocator to use.
[in]stringThe zero-terminated string to copy into the allocated buffer.
[in]lengthLength of the string to copy including the null termination character.
Returns
Pointer to the allocated buffer.

◆ outputString() [2/2]

char* cras::outputString ( allocator_t  allocator,
const std::string &  string 
)

Allocate enough bytes using the given allocator and copy the given string into the buffer (including null termination byte).

Parameters
[in]allocatorThe allocator to use.
[in]stringThe string to copy into the allocated buffer.
Returns
Pointer to the allocated buffer.

◆ paramsForNodeHandle()

inline ::cras::BoundParamHelperPtr cras::paramsForNodeHandle ( const ::ros::NodeHandle node)

Returns a param helper structure "bound" to the given node handle, so that it is not needed to specify the node handle in the subsequent getParam() calls.

Parameters
[in]nodeThe node to bind to.
Returns
The bound param helper.

Definition at line 264 of file node_utils.hpp.

◆ parseDouble() [1/2]

double cras::parseDouble ( const ::std::string &  string)

Parse the given string to a double.

Parameters
[in]stringThe string to parse.
Returns
The corresponding double value.
Exceptions
std::invalid_argumentIf the string does not represent a double value or if there are excess characters other than whitespace.

◆ parseDouble() [2/2]

double cras::parseDouble ( const char *  string)
inline

Parse the given string to a double.

Parameters
[in]stringThe string to parse.
Returns
The corresponding double value.
Exceptions
std::invalid_argumentIf the string does not represent a double value or if there are excess characters other than whitespace.

Definition at line 725 of file string_utils.hpp.

◆ parseFloat() [1/2]

float cras::parseFloat ( const ::std::string &  string)

Parse the given string to a float.

Parameters
[in]stringThe string to parse.
Returns
The corresponding float value.
Exceptions
std::invalid_argumentIf the string does not represent a float value or if there are excess characters other than whitespace.

◆ parseFloat() [2/2]

float cras::parseFloat ( const char *  string)
inline

Parse the given string to a float.

Parameters
[in]stringThe string to parse.
Returns
The corresponding float value.
Exceptions
std::invalid_argumentIf the string does not represent a float value or if there are excess characters other than whitespace.

Definition at line 704 of file string_utils.hpp.

◆ parseInt16() [1/2]

int16_t cras::parseInt16 ( const char *  string)
inline

Parse the given string to a 16-bit int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 16-bit int value.
Exceptions
std::invalid_argumentIf the string does not represent a 16-bit int value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

Definition at line 568 of file string_utils.hpp.

◆ parseInt16() [2/2]

int16_t cras::parseInt16 ( const std::string &  string)

Parse the given string to a 16-bit int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 16-bit int value.
Exceptions
std::invalid_argumentIf the string does not represent a 16-bit int value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

◆ parseInt32() [1/2]

int32_t cras::parseInt32 ( const char *  string)
inline

Parse the given string to a 32-bit int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 32-bit int value.
Exceptions
std::invalid_argumentIf the string does not represent a 32-bit int value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

Definition at line 614 of file string_utils.hpp.

◆ parseInt32() [2/2]

int32_t cras::parseInt32 ( const std::string &  string)

Parse the given string to a 32-bit int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 32-bit int value.
Exceptions
std::invalid_argumentIf the string does not represent a 32-bit int value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

◆ parseInt64() [1/2]

int64_t cras::parseInt64 ( const char *  string)
inline

Parse the given string to a 64-bit int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 64-bit int value.
Exceptions
std::invalid_argumentIf the string does not represent a 64-bit int value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

Definition at line 660 of file string_utils.hpp.

◆ parseInt64() [2/2]

int64_t cras::parseInt64 ( const std::string &  string)

Parse the given string to a 64-bit int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 64-bit int value.
Exceptions
std::invalid_argumentIf the string does not represent a 64-bit int value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

◆ parseInt8() [1/2]

int8_t cras::parseInt8 ( const char *  string)
inline

Parse the given string to a 8-bit int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 8-bit int value.
Exceptions
std::invalid_argumentIf the string does not represent a 8-bit int value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

Definition at line 522 of file string_utils.hpp.

◆ parseInt8() [2/2]

int8_t cras::parseInt8 ( const std::string &  string)

Parse the given string to a 8-bit int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 8-bit int value.
Exceptions
std::invalid_argumentIf the string does not represent a 8-bit int value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

◆ parseUInt16() [1/2]

uint16_t cras::parseUInt16 ( const char *  string)
inline

Parse the given string to a 16-bit unsigned int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 16-bit uint value.
Exceptions
std::invalid_argumentIf the string does not represent a 16-bit uint value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

Definition at line 591 of file string_utils.hpp.

◆ parseUInt16() [2/2]

uint16_t cras::parseUInt16 ( const std::string &  string)

Parse the given string to a 16-bit unsigned int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 16-bit uint value.
Exceptions
std::invalid_argumentIf the string does not represent a 16-bit uint value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

◆ parseUInt32() [1/2]

uint32_t cras::parseUInt32 ( const char *  string)
inline

Parse the given string to a 32-bit unsigned int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 32-bit uint value.
Exceptions
std::invalid_argumentIf the string does not represent a 32-bit uint value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

Definition at line 637 of file string_utils.hpp.

◆ parseUInt32() [2/2]

uint32_t cras::parseUInt32 ( const std::string &  string)

Parse the given string to a 32-bit unsigned int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 32-bit uint value.
Exceptions
std::invalid_argumentIf the string does not represent a 32-bit uint value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

◆ parseUInt64() [1/2]

uint64_t cras::parseUInt64 ( const char *  string)
inline

Parse the given string to a 64-bit unsigned int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 64-bit uint value.
Exceptions
std::invalid_argumentIf the string does not represent a 64-bit uint value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

Definition at line 683 of file string_utils.hpp.

◆ parseUInt64() [2/2]

uint64_t cras::parseUInt64 ( const std::string &  string)

Parse the given string to a 64-bit unsigned int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 64-bit uint value.
Exceptions
std::invalid_argumentIf the string does not represent a 64-bit uint value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

◆ parseUInt8() [1/2]

uint8_t cras::parseUInt8 ( const char *  string)
inline

Parse the given string to a 8-bit unsigned int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 8-bit uint value.
Exceptions
std::invalid_argumentIf the string does not represent a 8-bit uint value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

Definition at line 545 of file string_utils.hpp.

◆ parseUInt8() [2/2]

uint8_t cras::parseUInt8 ( const std::string &  string)

Parse the given string to a 8-bit unsigned int.

Parameters
[in]stringThe string to parse.
Returns
The corresponding 8-bit uint value.
Exceptions
std::invalid_argumentIf the string does not represent a 8-bit uint value or if there are excess characters other than whitespace.
Note
This function supports hexadecimal numbers starting with 0x/0X, binary numbers with 0b/0B and octal with 0.

◆ prependIfNonEmpty()

::std::string cras::prependIfNonEmpty ( const ::std::string &  str,
const ::std::string &  prefix 
)

If str is nonempty, returns prefix + str, otherwise empty string.

Parameters
[in]strThe main string.
[in]prefixThe string's prefix.
Returns
The possibly prefixed string.

◆ quoteIfStringType()

template<typename T , ::std::enable_if_t<!::cras::is_string<::std::decay_t< T >>::value, bool > = true>
inline ::std::string cras::quoteIfStringType ( const ::std::string &  s,
const T &   
)

Put s in double quotes if T is a string type (std::string or char*).

Template Parameters
TThe type to check.
Parameters
[in]sThe input string.
Returns
Either s in double quotes if T is a string type, or just s.

Definition at line 297 of file string_utils.hpp.

◆ registerCloudChannelType()

void cras::registerCloudChannelType ( const ::std::string &  channelPrefix,
::cras::CloudChannelType  type 
)

Register the given pointcloud channel prefix with the given type. This registration will be used by transformWithChannels() when called without an explicit channel list.

Parameters
[in]channelPrefixPrefix of the channel. E.g. normal_ for registering type of normal_x,normal_y,normal_z.
[in]typeType of the channel.

◆ remainingTime() [1/2]

::ros::Duration cras::remainingTime ( const ::ros::Time query,
const ::ros::Duration timeout 
)

Return remaining time to timeout from the query time.

Parameters
[in]queryThe query time, e.g. of a TF.
[in]timeoutMaximum time to wait from the query time onwards.
Returns
The remaining time.

◆ remainingTime() [2/2]

::ros::Duration cras::remainingTime ( const ::ros::Time query,
double  timeout 
)

Return remaining time to timeout from the query time.

Parameters
[in]queryThe query time, e.g. of a TF.
[in]timeoutMaximum time to wait from the query time onwards.
Returns
The remaining time.

◆ removePrefix()

::std::string cras::removePrefix ( const ::std::string &  str,
const ::std::string &  prefix,
bool *  hadPrefix = nullptr 
)

Remove prefix from start of str if it contains it, otherwise return str unchanged.

Parameters
[in]strThe string to work on.
[in]prefixThe prefix to find.
[in]hadPrefixIf non-null, will contain information whether str starts with prefix.
Returns
If str starts with prefix, it will return str with prefix removed. Otherwise, str will be returned unchanged.

◆ removeSuffix()

::std::string cras::removeSuffix ( const ::std::string &  str,
const ::std::string &  suffix,
bool *  hadSuffix = nullptr 
)

Remove suffix from end of str if it contains it, otherwise return str unchanged.

Parameters
[in]strThe string to work on.
[in]suffixThe suffix to find.
[in]hadSuffixIf non-null, will contain information whether str ends with suffix.
Returns
If str ends with suffix, it will return str with suffix removed. Otherwise, str will be returned unchanged.

◆ replace() [1/2]

void cras::replace ( ::std::string &  str,
const ::std::string &  from,
const ::std::string &  to,
const ::cras::ReplacePosition where = ::cras::ReplacePosition::EVERYWHERE 
)

Replace all occurrences of from in str with to.

Parameters
[in,out]strThe string to replace in.
[in]fromThe string to replace.
[in]toThe replacement.
[in]whereWhere to do the replacement.

◆ replace() [2/2]

::std::string cras::replace ( const ::std::string &  str,
const ::std::string &  from,
const ::std::string &  to,
const ::cras::ReplacePosition where = ::cras::ReplacePosition::EVERYWHERE 
)

Replace all occurrences of from in str with to.

Parameters
[in]strThe string to replace in.
[in]fromThe string to replace.
[in]toThe replacement.
[in]whereWhere to do the replacement.
Returns
str with all occurrences of from replaced with to.

◆ rosgraphMsgLevelToLogLevel()

::ros::console::Level cras::rosgraphMsgLevelToLogLevel ( uint8_t  msgLevel)

Convert the given rosgraph_msgs::Log level constant to rosconsole logging level.

Parameters
[in]msgLevelA rosgraph_msgs::Log level constant.
Returns
The rosconsole logging level.

◆ safeRate()

::ros::Rate cras::safeRate ( double  frequency)

Return a rate representing the given frequency. If the frequency is zero or too small, return min/max representable rate.

Parameters
[in]frequencyThe frequency to convert.
Returns
The corresponding Rate object.

◆ safeWallRate()

::ros::WallRate cras::safeWallRate ( double  frequency)

Return a rate representing the given frequency. If the frequency is zero or too small, return min/max representable rate.

Parameters
[in]frequencyThe frequency to convert.
Returns
The corresponding Rate object.

◆ saturateAdd() [1/3]

::ros::SteadyTime cras::saturateAdd ( const ::ros::SteadyTime time,
const ::ros::WallDuration duration 
)

Add the given duration to the given time, but saturate the result instead of throwing exception on overflow.

Parameters
[in]timeThe time to be added to.
[in]durationThe duration to add.
Returns
The time plus the duration saturated between 0 and TIME_MAX.

◆ saturateAdd() [2/3]

::ros::Time cras::saturateAdd ( const ::ros::Time time,
const ::ros::Duration duration 
)

Add the given duration to the given time, but saturate the result instead of throwing exception on overflow.

Parameters
[in]timeThe time to be added to.
[in]durationThe duration to add.
Returns
The time plus the duration saturated between 0 and TIME_MAX.

◆ saturateAdd() [3/3]

::ros::WallTime cras::saturateAdd ( const ::ros::WallTime time,
const ::ros::WallDuration duration 
)

Add the given duration to the given time, but saturate the result instead of throwing exception on overflow.

Parameters
[in]timeThe time to be added to.
[in]durationThe duration to add.
Returns
The time plus the duration saturated between 0 and TIME_MAX.

◆ setThreadName()

void cras::setThreadName ( const std::string &  name)

Set the OS name of the current thread.

Parameters
[in]nameThe name to set.
Note
The name will be automatically shortened to be 15 chars max.
This function is actually pretty fast. It can be called more than 1 million times per second.

◆ sizeOfPointField() [1/2]

size_t cras::sizeOfPointField ( const ::sensor_msgs::PointField &  field)

Return the size (in bytes) of the data represented by the sensor_msgs::PointField.

Parameters
[in]fieldThe pointfield specification.
Returns
Size of the data.
Exceptions
std::runtime_errorif wrong datatype is passed.

◆ sizeOfPointField() [2/2]

size_t cras::sizeOfPointField ( int  datatype)

Return the size (in bytes) of a sensor_msgs::PointField datatype.

Parameters
[in]datatypeThe datatype (one of sensor_msgs::PointField::(U?INT(8|16|32)|FLOAT(32|64)) constants).
Returns
Size of the datatype in bytes.
Exceptions
std::runtime_errorif wrong datatype is passed.

◆ split()

::std::vector<::std::string> cras::split ( const ::std::string &  str,
const ::std::string &  delimiter,
int  maxSplits = -1 
)

Split the given string by the given delimiter.

Parameters
[in]strThe string to split.
[in]delimiterThe delimiter used for splitting.
[in]maxSplitsIf >= 0, defines the maximum number of splits.
Returns
A vector of parts of the original string.

◆ startsWith()

bool cras::startsWith ( const ::std::string &  str,
const ::std::string &  prefix 
)

Check whether prefix is a prefix of str.

Parameters
[in]strThe string to be searched in.
[in]prefixThe string to be found in str.
Returns
Whether prefix is a prefix of str.

◆ strip() [1/2]

void cras::strip ( ::std::string &  s,
const char &  c = ' ' 
)

Strip c from the beginning and end of the given string (if it is there).

Parameters
[in,out]sThe string from which c should be removed.
[in]cThe character to remove.

◆ strip() [2/2]

::std::string cras::strip ( const ::std::string &  s,
const char &  c = ' ' 
)

Return a copy of the given string with c removed from its beginning and end (if it was there).

Parameters
[in]sThe string from which c should be removed.
[in]cThe character to remove.
Returns
The string without c at the beginning and end.

◆ stripLeading() [1/2]

void cras::stripLeading ( ::std::string &  s,
const char &  c = ' ' 
)

Strip c from the start of the given string (if there is one).

Parameters
[in,out]sThe string from which c should be removed.
[in]cThe character to remove.

◆ stripLeading() [2/2]

::std::string cras::stripLeading ( const ::std::string &  s,
const char &  c = ' ' 
)

Return a copy of the given string with c removed from its start (if there is one).

Parameters
[in]sThe string from which c should be removed.
[in]cThe character to remove.
Returns
The string without c at the start.

◆ stripLeadingSlash() [1/2]

void cras::stripLeadingSlash ( ::std::string &  s,
bool  warn = false 
)

Strip leading slash from the given string (if there is one).

Parameters
[in,out]sThe string from which slash should be removed.
[in]warnIf true, issue a ROS warning if the string contained the leading slash.

◆ stripLeadingSlash() [2/2]

::std::string cras::stripLeadingSlash ( const ::std::string &  s,
bool  warn = false 
)

Return a copy of the given string with leading slash removed (if there is one).

Parameters
[in]sThe string from which slash should be removed.
[in]warnIf true, issue a ROS warning if the string contained the leading slash.
Returns
The string without leading slash.

◆ stripTrailing() [1/2]

void cras::stripTrailing ( ::std::string &  s,
const char &  c = ' ' 
)

Strip c from the end of the given string (if there is one).

Parameters
[in,out]sThe string from which c should be removed.
[in]cThe character to remove.

◆ stripTrailing() [2/2]

::std::string cras::stripTrailing ( const ::std::string &  s,
const char &  c = ' ' 
)

Return a copy of the given string with c removed from its end (if there is one).

Parameters
[in]sThe string from which c should be removed.
[in]cThe character to remove.
Returns
The string without c at the end.

◆ to_cstring()

constexpr const char* cras::to_cstring ( const ::XmlRpc::XmlRpcValue::Type value)
constexpr

Return a string representation of the XmlRpcValue type.

Parameters
[in]valueThe value to get type of.
Returns
The string representation of the XmlRpcValue type.

Definition at line 33 of file xmlrpc_value_traits.hpp.

◆ to_string() [1/24]

inline ::std::string cras::to_string ( char *  value)

Definition at line 361 of file string_utils.hpp.

◆ to_string() [2/24]

template<typename Scalar , int Rows, int Cols, int Options, int MaxRows, int MaxCols>
inline ::std::string cras::to_string ( const ::Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols > &  value)

Definition at line 21 of file string_utils/eigen.hpp.

◆ to_string() [3/24]

template<typename Derived , int Dim>
inline ::std::string cras::to_string ( const ::Eigen::RotationBase< Derived, Dim > &  value)

Definition at line 29 of file string_utils/eigen.hpp.

◆ to_string() [4/24]

template<typename Scalar , int Dim, int Mode, int Options>
inline ::std::string cras::to_string ( const ::Eigen::Transform< Scalar, Dim, Mode, Options > &  value)

Definition at line 37 of file string_utils/eigen.hpp.

◆ to_string() [5/24]

template<typename T , size_t N>
inline ::std::string cras::to_string ( const ::std::array< T, N > &  value)

Definition at line 440 of file string_utils.hpp.

◆ to_string() [6/24]

template<typename K , typename V >
inline ::std::string cras::to_string ( const ::std::map< K, V > &  value)

◆ to_string() [7/24]

inline ::std::string cras::to_string ( const ::std::string &  value)

Definition at line 383 of file string_utils.hpp.

◆ to_string() [8/24]

template<typename K , typename V >
inline ::std::string cras::to_string ( const ::std::unordered_map< K, V > &  value)

◆ to_string() [9/24]

inline ::std::string cras::to_string ( const ::tf2::Matrix3x3 value)

Definition at line 36 of file string_utils/tf2.hpp.

◆ to_string() [10/24]

inline ::std::string cras::to_string ( const ::tf2::Quaternion value)

Definition at line 26 of file string_utils/tf2.hpp.

◆ to_string() [11/24]

inline ::std::string cras::to_string ( const ::tf2::Transform value)

Definition at line 44 of file string_utils/tf2.hpp.

◆ to_string() [12/24]

inline ::std::string cras::to_string ( const ::tf2::Vector3 &  value)

Definition at line 21 of file string_utils/tf2.hpp.

◆ to_string() [13/24]

inline ::std::string cras::to_string ( const ::XmlRpc::XmlRpcValue value)

Definition at line 18 of file xmlrpc.hpp.

◆ to_string() [14/24]

template<>
inline ::std::string cras::to_string ( const ::XmlRpc::XmlRpcValue::Type value)

Definition at line 60 of file xmlrpc_value_traits.hpp.

◆ to_string() [15/24]

inline ::std::string cras::to_string ( const bool &  value)

Definition at line 378 of file string_utils.hpp.

◆ to_string() [16/24]

inline ::std::string cras::to_string ( const char *  value)

Definition at line 356 of file string_utils.hpp.

◆ to_string() [17/24]

template<int I>
inline ::std::string cras::to_string ( const char  value[I])

Definition at line 367 of file string_utils.hpp.

◆ to_string() [18/24]

inline ::std::string cras::to_string ( const double &  value)

Definition at line 341 of file string_utils.hpp.

◆ to_string() [19/24]

inline ::std::string cras::to_string ( const float &  value)

Definition at line 346 of file string_utils.hpp.

◆ to_string() [20/24]

inline ::std::string cras::to_string ( const long double &  value)

Definition at line 351 of file string_utils.hpp.

◆ to_string() [21/24]

template<typename M , ::std::enable_if_t<::ros::message_traits::IsMessage< M >::value > * = nullptr>
std::string cras::to_string ( const M &  msg)
inline

Definition at line 51 of file string_utils/ros.hpp.

◆ to_string() [22/24]

template<typename T , typename ::std::enable_if_t< ::std::is_same< T, ::ros::Time >::value||::std::is_same< T, ::ros::WallTime >::value||::std::is_same< T, ::ros::SteadyTime >::value||::std::is_same< T, ::ros::Duration >::value||::std::is_same< T, ::ros::WallDuration >::value > * = nullptr>
inline ::std::string cras::to_string ( const T &  value)

Definition at line 32 of file string_utils/ros.hpp.

◆ to_string() [23/24]

template<typename T >
decltype(::std::to_string(::std::declval<T>())) cras::to_string ( const T &  value)
inline

Convert the given value to a string representation.

Template Parameters
TType of the value.
Parameters
[in]valueThe value to convert.
Returns
The string representation.

Definition at line 321 of file string_utils.hpp.

◆ to_string() [24/24]

template<typename T >
decltype(static_cast<::std::string>(::std::declval<T>())) cras::to_string ( const T &  value)
inline

Convert the given value to a string representation.

Template Parameters
TType of the value.
Parameters
[in]valueThe value to convert.
Returns
The string representation.

Definition at line 333 of file string_utils.hpp.

◆ toEigen() [1/3]

::Eigen::Isometry3d cras::toEigen ( const ::urdf::Pose &  pose)

Convert URDF pose to Eigen transform.

Parameters
[in]poseThe pose to convert.
Returns
The corresponding Eigen transform.

◆ toEigen() [2/3]

::Eigen::Quaterniond cras::toEigen ( const ::urdf::Rotation &  rotation)

Convert URDF rotation to Eigen quaternion.

Parameters
[in]rotationThe rotation to convert.
Returns
The corresponding Eigen quaternion.

◆ toEigen() [3/3]

::Eigen::Translation3d cras::toEigen ( const ::urdf::Vector3 &  position)

URDF Vector3 to Eigen translation.

Parameters
[in]positionThe vector to convert.
Returns
The corresponding Eigen translation.

◆ toLower()

::std::string cras::toLower ( const ::std::string &  str)

Convert all characters in the given string to lower case.

Parameters
[in]strThe input string.
Returns
A copy of the input string with all characters lower case. The string does not necessarily be of the same length as the input string (but it will be 99% of the cases).

◆ toUpper()

::std::string cras::toUpper ( const ::std::string &  str)

Convert all characters in the given string to upper case.

Parameters
[in]strThe input string.
Returns
A copy of the input string with all characters upper case. The string does not necessarily be of the same length as the input string (but it will be 99% of the cases).

◆ toURDF() [1/4]

::urdf::Pose cras::toURDF ( const ::Eigen::Isometry3d &  pose)

Convert Eigen isometry to URDF Pose.

Parameters
[in]poseThe pose to convert.
Returns
The corresponding URDF Pose.

◆ toURDF() [2/4]

::urdf::Rotation cras::toURDF ( const ::Eigen::Quaterniond &  rotation)

Convert Eigen quaternion to URDF Rotation.

Parameters
[in]rotationThe quaternion to convert.
Returns
The corresponding URDF Rotation.

◆ toURDF() [3/4]

::urdf::Vector3 cras::toURDF ( const ::Eigen::Translation3d &  translation)

Convert Eigen translation to URDF Vector3.

Parameters
[in]translationThe translation to convert.
Returns
The corresponding URDF Vector3.

◆ toURDF() [4/4]

::urdf::Vector3 cras::toURDF ( const ::Eigen::Vector3d &  vector)

Convert Eigen vector to URDF Vector3.

Parameters
[in]vectorThe vector to convert.
Returns
The corresponding URDF Vector3.

◆ transformChannel()

void cras::transformChannel ( ::sensor_msgs::PointCloud2 &  cloud,
const ::geometry_msgs::Transform &  transform,
const ::std::string &  channelPrefix,
::cras::CloudChannelType  type 
)

Transform the given channel in the given cloud using the given transform.

Parameters
[in,out]cloudThe cloud.
[in]transformThe transform to apply.
[in]channelPrefixPrefix of the channel.
[in]typeType of the channel.

◆ transformOnlyChannels()

::sensor_msgs::PointCloud2& cras::transformOnlyChannels ( const ::sensor_msgs::PointCloud2 &  in,
::sensor_msgs::PointCloud2 &  out,
const ::geometry_msgs::TransformStamped &  tf,
const ::std::unordered_map<::std::string, ::cras::CloudChannelType > &  channels 
)

Copy the selected channels from in cloud to out and transform them using the given transform.

Parameters
[in]inThe input cloud.
[out]outThe output cloud (can not be the same as input).
[in]tfThe transform to apply.
[in]channelsA map of channel prefix-channel type of channels that should be transformed. No other channels will be present in the output cloud.
Returns
out.

◆ transformOnlyXYZ()

::sensor_msgs::PointCloud2& cras::transformOnlyXYZ ( const ::sensor_msgs::PointCloud2 &  in,
::sensor_msgs::PointCloud2 &  out,
const ::geometry_msgs::TransformStamped &  tf 
)

Copy only the XYZ channel from in cloud to out and transform it using the given transform.

Parameters
[in]inThe input cloud.
[out]outThe output cloud (can not be the same as input).
[in]tfThe transform to apply.
Returns
out.

◆ transformWithChannels() [1/4]

::sensor_msgs::PointCloud2& cras::transformWithChannels ( const ::sensor_msgs::PointCloud2 &  in,
::sensor_msgs::PointCloud2 &  out,
const ::geometry_msgs::TransformStamped &  tf 
)

Copy in cloud to out and transform channels using the given transform. The list of channels to be transformed consists of the XYZ channel, vp_, normal_ and all channels registered by registerCloudChannelType().

Parameters
[in]inThe input cloud.
[out]outThe output cloud (can be the same as input).
[in]tfThe transform to apply.
Returns
out.

◆ transformWithChannels() [2/4]

::sensor_msgs::PointCloud2& cras::transformWithChannels ( const ::sensor_msgs::PointCloud2 &  in,
::sensor_msgs::PointCloud2 &  out,
const ::geometry_msgs::TransformStamped &  tf,
const ::std::unordered_map<::std::string, ::cras::CloudChannelType > &  channels 
)

Copy in cloud to out and transform channels using the given transform. Only the channels passed in channels will be transformed, according to their type.

Parameters
[in]inThe input cloud.
[out]outThe output cloud (can be the same as input).
[in]tfThe transform to apply.
[in]channelsA map of channel prefix-channel type of channels that should be transformed.
Returns
out.

◆ transformWithChannels() [3/4]

::sensor_msgs::PointCloud2& cras::transformWithChannels ( const ::sensor_msgs::PointCloud2 &  in,
::sensor_msgs::PointCloud2 &  out,
const ::tf2_ros::Buffer tfBuffer,
const ::std::string &  targetFrame 
)

Copy in cloud to out and transform channels using the given transform. The list of channels to be transformed consists of the XYZ channel, vp_, normal_ and all channels registered by registerCloudChannelType().

Parameters
[in]inThe input cloud.
[out]outThe output cloud (can be the same as input).
[in]tfBufferThe TF buffer.
[in]targetFrameThe frame to transform to.
Returns
out.
Exceptions
tf2::TransformExceptionNo exceptions thrown from lookupTransform() will be catched.

◆ transformWithChannels() [4/4]

::sensor_msgs::PointCloud2& cras::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 
)

Copy in cloud to out and transform channels using the given transform. Only the channels passed in channels will be transformed, according to their type.

Parameters
[in]inThe input cloud.
[out]outThe output cloud (can be the same as input).
[in]tfBufferThe TF buffer.
[in]targetFrameThe frame to transform to.
[in]channelsA map of channel prefix-channel type of channels that should be transformed.
Returns
out.
Exceptions
tf2::TransformExceptionNo exceptions thrown from lookupTransform() will be catched.

◆ unregisterCloudChannelType()

void cras::unregisterCloudChannelType ( const ::std::string &  channelPrefix)

Unregister a cloud channel type registered earlier with registerCloudChannelType().

Parameters
[in]channelPrefixPrefix of the channel.

Variable Documentation

◆ int

LONG_MAX USHRT_MAX cras::int

Definition at line 123 of file xmlrpc_value_utils.hpp.

◆ LONG_MIN

cras::LONG_MIN

Definition at line 123 of file xmlrpc_value_utils.hpp.

◆ paramHelper

const ParamHelper cras::paramHelper(::std::make_shared<::cras::NodeLogHelper >())

Static variable that serves as the singleton for getting node parameters.



cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:14