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... | |
struct | DurationType |
struct | DurationType< ros::SteadyTime > |
struct | DurationType< ros::Time > |
struct | DurationType< ros::WallTime > |
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 | OfflineDiagUpdater |
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 | SmallMap |
Simple map implemented on top of a std::list<std::pair>. The map is append-only, with lock-free reads and mutex-protected insert. More... | |
class | SmallSet |
Simple set implemented on top of a std::list. The set is append-only, with lock-free reads and mutex-protected insert. 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 | TempLocale |
Helper class for temporarily setting locale in a RAII manner. 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::BoundParamHelper > | BoundParamHelperPtr |
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< int > | CloudIndexConstIter |
Const cloud int field iterator. More... | |
typedef ::sensor_msgs::PointCloud2Iterator< int > | CloudIndexIter |
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::GetParamAdapter > | GetParamAdapterPtr |
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::ParamHelper > | ParamHelperPtr |
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 | |
__attribute__ ((format(printf, 1, 0))) inline | |
__attribute__ ((format(printf, 1, 2))) inline | |
::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) |
template<typename D1 , typename D2 , typename ::std::enable_if_t< ::std::is_same< D1, ::ros::Duration >::value||::std::is_same< D1, ::ros::WallDuration >::value > * = nullptr, typename ::std::enable_if_t< ::std::is_same< D2, ::ros::Duration >::value||::std::is_same< D2, ::ros::WallDuration >::value > * = nullptr> | |
D1 | convertDuration (const D2 &duration) |
template<typename T1 , typename T2 , typename ::std::enable_if_t< ::std::is_same< T1, ::ros::Time >::value||::std::is_same< T1, ::ros::WallTime >::value||::std::is_same< T1, ::ros::SteadyTime >::value > * = nullptr, typename ::std::enable_if_t< ::std::is_same< T2, ::ros::Time >::value||::std::is_same< T2, ::ros::WallTime >::value||::std::is_same< T2, ::ros::SteadyTime >::value > * = nullptr> | |
T1 | convertTime (const T2 &time) |
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,...) |
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 ¶m, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}, const ::cras::LogHelper *const logger=nullptr) |
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 ¶m, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr) |
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 ¶m, 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 ¶m, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr) |
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 ¶m, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}, const ::cras::LogHelper *const logger=nullptr) |
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 ¶m, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr) |
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 ¶m, 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 ¶m, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}, const ::cras::LogHelper *const logger=nullptr) |
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... | |
::std::string | iconvConvert (const ::std::string &toEncoding, const ::std::string &fromEncoding, const ::std::string &inText, bool translit=false, bool ignore=false, double initialOutbufSizeScale=1.0, double outbufEnlargeCoef=2.0, const ::cras::optional<::std::string > &localeName=::cras::nullopt) |
Convert inText from fromEncoding to toEncoding using iconv. More... | |
bool | isLegalBaseName (const ::std::string &name) |
Validates that name is a legal base name for a graph resource. A base name has no namespace context, e.g. "node_name". More... | |
bool | isLegalName (const ::std::string &name) |
Check if name is a legal ROS name for graph resources. 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... | |
template<typename D = ::ros::Duration, typename ::std::enable_if_t< ::std::is_same< D, ::ros::Duration >::value||::std::is_same< D, ::ros::WallDuration >::value > * = nullptr> | |
D | parseDuration (const ::std::string &s) |
Parse the given string as duration. 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 char *string, const uint8_t base) |
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... | |
int16_t | parseInt16 (const std::string &string, uint8_t base) |
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 char *string, const uint8_t base) |
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... | |
int32_t | parseInt32 (const std::string &string, uint8_t base) |
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 char *string, const uint8_t base) |
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... | |
int64_t | parseInt64 (const std::string &string, uint8_t base) |
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 char *string, const uint8_t base) |
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... | |
int8_t | parseInt8 (const std::string &string, uint8_t base) |
Parse the given string to a 8-bit int. More... | |
template<typename T = ::ros::Time, 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 > * = nullptr> | |
T | parseTime (const ::std::string &s, const ::cras::optional< typename ::cras::DurationType< T >::value > &timezoneOffset={}, const T &referenceDate={}) |
Parse the given string as time. More... | |
template<typename D = ::ros::Duration, typename ::std::enable_if_t< ::std::is_same< D, ::ros::Duration >::value||::std::is_same< D, ::ros::WallDuration >::value > * = nullptr> | |
D | parseTimezoneOffset (const ::std::string &s) |
Parse timezone offset from the given string. More... | |
uint16_t | parseUInt16 (const char *string) |
Parse the given string to a 16-bit unsigned int. More... | |
uint16_t | parseUInt16 (const char *string, const uint8_t base) |
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... | |
uint16_t | parseUInt16 (const std::string &string, uint8_t base) |
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 char *string, const uint8_t base) |
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... | |
uint32_t | parseUInt32 (const std::string &string, uint8_t base) |
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 char *string, const uint8_t base) |
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... | |
uint64_t | parseUInt64 (const std::string &string, uint8_t base) |
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 char *string, const uint8_t base) |
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... | |
uint8_t | parseUInt8 (const std::string &string, uint8_t base) |
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... | |
::std::string | toValidRosName (const ::std::string &text, bool baseName=true, const ::cras::optional<::std::string > &fallbackName=::cras::nullopt) |
Make sure the given string can be used as ROS name. 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... | |
::std::string | transliterateToAscii (const ::std::string &text) |
Transliterate the given string from UTF-8 to ASCII (replace non-ASCII chars by closest ASCII chars). 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 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.
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.
typedef ::std::shared_ptr<::cras::BoundParamHelper> cras::BoundParamHelperPtr |
Definition at line 24 of file bound_param_helper.hpp.
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.
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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.
typedef ::sensor_msgs::PointCloud2 cras::Cloud |
typedef ::sensor_msgs::PointCloud2ConstIterator<float> cras::CloudConstIter |
typedef ::sensor_msgs::PointCloud2Iterator<float> cras::CloudIter |
Shorthand for sensor_msgs::PointCloud2Modifier.
using cras::DurationStatusPtr = typedef ::std::shared_ptr<::cras::DurationStatus> |
Definition at line 140 of file duration_status.h.
typedef ::cras::impl::GenericCloudConstIterator cras::GenericCloudConstIter |
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.
typedef ::std::shared_ptr<::cras::GetParamAdapter> cras::GetParamAdapterPtr |
Definition at line 57 of file get_param_adapter.hpp.
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.
Const pointer to LogHelper
.
Definition at line 203 of file log_utils.h.
typedef ::cras::LogHelper::Ptr cras::LogHelperPtr |
Pointer to LogHelper
.
Definition at line 202 of file log_utils.h.
typedef ::std::shared_ptr<::cras::ParamHelper> cras::ParamHelperPtr |
Definition at line 266 of file param_utils/param_helper.hpp.
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.
Message | Type of the message for which parameters are constructed. |
Definition at line 80 of file topic_status_param.hpp.
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.
Message | Type of the message for which parameters are constructed. |
cras::FrequencyStatusParam
or cras::TopicStatusParamWithHeader
based on the type of the message. Definition at line 280 of file topic_status_param.hpp.
using cras::TopicStatusPtr = typedef ::std::shared_ptr<::cras::TopicStatus<Message> > |
Definition at line 250 of file topic_status.hpp.
using cras::ToStringFn = typedef ::std::function<::std::string(const T&)> |
Type of function that converts anything to a string.
Definition at line 349 of file string_utils.hpp.
enum cras::chars_format |
Enumerator | |
---|---|
scientific | |
fixed | |
hex | |
general |
Definition at line 17 of file from_chars.h.
|
strong |
Type of a pointcloud channel.
Definition at line 25 of file tf2_sensor_msgs.h.
|
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 147 of file string_utils.hpp.
cras::__attribute__ | ( | (format(printf, 1, 0)) | ) |
printf-like support working with std::string and automatically managing memory.
[in] | format | The printf-like format string. |
[in] | args | Arguments of the format string. |
Definition at line 227 of file string_utils.hpp.
cras::__attribute__ | ( | (format(printf, 1, 2)) | ) |
printf-like support working with std::string and automatically managing memory.
[in] | format | The printf-like format string. |
[in] | ... | Arguments of the format string. |
Definition at line 264 of file string_utils.hpp.
::std::string cras::appendIfNonEmpty | ( | const ::std::string & | str, |
const ::std::string & | suffix | ||
) |
If str
is nonempty, returns str + suffix, otherwise empty string.
[in] | str | The main string. |
[in] | suffix | The string's suffix. |
auto cras::bind_front | ( | F && | f, |
Args &&... | args | ||
) |
Definition at line 48 of file functional.hpp.
::std::string cras::cleanTypeName | ( | const ::std::string & | typeName | ) |
Remove not-so-nice parts of demangled C++ type names.
[in] | typeName | Name of a demangled C++ type. |
bool cras::contains | ( | const ::std::string & | str, |
char | c | ||
) |
Check whether str
contains character c
.
[in] | str | The string to search in. |
[in] | c | The character to search. |
str
contains character c
. bool cras::contains | ( | const ::std::string & | str, |
const ::std::string & | needle | ||
) |
Check whether str
contains substring needle
.
[in] | str | The string to search in. |
[in] | needle | The substring to search. |
str
contains substring needle
.
|
inline |
Definition at line 311 of file xmlrpc_value_utils.hpp.
|
inline |
Definition at line 260 of file xmlrpc_value_utils.hpp.
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
Convert XmlRpcValue x
to value v
.
[in] | x | The XmlRpcValue to convert. |
[out] | v | The value to convert to. |
[in,out] | errors | If non-null, any conversion error messages will be stored here. |
Definition at line 55 of file xmlrpc_value_utils.hpp.
|
inline |
Definition at line 63 of file xmlrpc_value_utils.hpp.
|
inline |
Definition at line 135 of file xmlrpc_value_utils.hpp.
|
inline |
Definition at line 89 of file xmlrpc_value_utils.hpp.
|
inline |
Definition at line 181 of file xmlrpc_value_utils.hpp.
|
inline |
Definition at line 69 of file time_utils.hpp.
|
inline |
Definition at line 54 of file time_utils.hpp.
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.
[in] | in | The input cloud. |
[out] | out | The 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] | fieldName | Name of the field whose data should be copied. |
std::runtime_error | If the output cloud is smaller (in nr. of points) than the input cloud. |
std::runtime_error | If the given field doesn't exist in either of the clouds. |
cras::DEFINE_CONVERTING_GET_PARAM | ( | ::Eigen::Vector3d | , |
::std::vector< double > | , | ||
"" | , | ||
[] (const ::std::vector< double > &v){ checkSize(v, 3, "vector");return ::Eigen::Vector3d(v.data());} | |||
) |
Definition at line 31 of file param_utils/get_param_specializations/eigen.hpp.
cras::DEFINE_CONVERTING_GET_PARAM | ( | ::Eigen::Vector4d | , |
::std::vector< double > | , | ||
"" | , | ||
[] (const ::std::vector< double > &v){ checkSize(v, 4, "vector");return ::Eigen::Vector4d(v.data());} | |||
) |
Definition at line 37 of file param_utils/get_param_specializations/eigen.hpp.
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.
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]);} | |||
) |
Definition at line 24 of file param_utils/get_param_specializations/tf2.hpp.
LONG_MAX cras::DEFINE_INTEGRAL_CONVERT | ( | long long | , |
int | , | ||
LONG_LONG_MIN | , | ||
LONG_LONG_MAX | |||
) |
cras::DEFINE_INTEGRAL_CONVERT | ( | short | , |
int | , | ||
SHRT_MIN | , | ||
SHRT_MAX | |||
) |
LONG_MAX USHRT_MAX cras::DEFINE_INTEGRAL_CONVERT | ( | unsigned long | , |
int | , | ||
0 | , | ||
ULONG_MAX | |||
) |
::std::string cras::demangle | ( | const ::std::string & | mangled | ) |
Demangle the given mangle C++ type identifier.
[in] | mangled | The mangled name. |
mangled
. bool cras::endsWith | ( | const ::std::string & | str, |
const ::std::string & | suffix | ||
) |
Check whether suffix
is a suffix of str
.
[in] | str | The string to be searched in. |
[in] | suffix | The string to be found in str . |
suffix
is a suffix of str
. inline ::std::string cras::format | ( | ::std::string | format, |
::va_list | args | ||
) |
printf-like support working with std::string and automatically managing memory.
[in] | format | The printf-like format string. |
[in] | args | Arguments of the format string. |
Definition at line 295 of file string_utils.hpp.
inline ::std::string cras::format | ( | ::std::string | format, |
... | |||
) |
printf-like support working with std::string and automatically managing memory.
[in] | format | The printf-like format string. |
[in] | ... | Arguments of the format string. |
Definition at line 280 of file string_utils.hpp.
double cras::frequency | ( | const ::ros::Rate & | rate, |
bool | maxCycleTimeMeansZero = false |
||
) |
Return the frequency represented by the given rate.
[in] | rate | The rate to convert. |
[in] | maxCycleTimeMeansZero | If true, return 0 frequency in case the rate's cycle time is the maximum duration. |
double cras::frequency | ( | const ::ros::WallRate & | rate, |
bool | maxCycleTimeMeansZero = false |
||
) |
Return the frequency represented by the given rate.
[in] | rate | The rate to convert. |
[in] | maxCycleTimeMeansZero | If true, return 0 frequency in case the rate's cycle time is the maximum duration. |
|
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.
[in] | string | The string to convert. |
[out] | value | The parsed value (valid only if parsing succeeded, i.e. ec in the result is 0). |
[in] | fmt | Bitmask of cras::chars_format values that specify the format rules with which the value should be interpreted. Not all formats have to be supported. |
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.
|
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.
[in] | string | The string to convert. |
[out] | value | The parsed value (valid only if parsing succeeded, i.e. ec in the result is 0). |
[in] | fmt | Bitmask of cras::chars_format values that specify the format rules with which the value should be interpreted. Not all formats have to be supported. |
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.
|
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.
[in] | first | Pointer to first char of the string. |
[in] | last | Pointer to last char of the string. |
[out] | value | The parsed value (valid only if parsing succeeded, i.e. ec in the result is 0). |
[in] | fmt | Bitmask of cras::chars_format values that specify the format rules with which the value should be interpreted. Not all formats have to be supported. |
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.
|
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.
[in] | first | Pointer to first char of the string. |
[in] | last | Pointer to last char of the string. |
[out] | value | The parsed value (valid only if parsing succeeded, i.e. ec in the result is 0). |
[in] | fmt | Bitmask of cras::chars_format values that specify the format rules with which the value should be interpreted. Not all formats have to be supported. |
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. ::sensor_msgs::PointField& cras::getField | ( | ::cras::Cloud & | cloud, |
const ::std::string & | fieldName | ||
) |
Return the sensor_msgs::PointField with the given name.
[in] | cloud | Cloud to extract the field from. |
[in] | fieldName | Name of the field. |
std::runtime_error | if the field doesn't exist. |
const ::sensor_msgs::PointField& cras::getField | ( | const ::cras::Cloud & | cloud, |
const ::std::string & | fieldName | ||
) |
Return the sensor_msgs::PointField with the given name.
[in] | cloud | Cloud to extract the field from. |
[in] | fieldName | Name of the field. |
std::runtime_error | if the field doesn't exist. |
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.
[in] | param | The parameter adapter from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
[in] | logger | The LogHelper used for printing messages. If nullptr, no messages are printed. |
Definition at line 441 of file param_utils.hpp.
|
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).
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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. |
[in] | param | The parameter adapter from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
[in] | logger | The LogHelper used for printing messages. If nullptr, no messages are printed. |
Definition at line 335 of file param_utils.hpp.
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.
[in] | param | The parameter adapter from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
[in] | logger | The LogHelper used for printing messages. If nullptr, no messages are printed. |
Definition at line 463 of file param_utils.hpp.
|
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).
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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. |
[in] | param | The parameter adapter from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
[in] | logger | The LogHelper used for printing messages. If nullptr, no messages are printed. |
Definition at line 365 of file param_utils.hpp.
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.
[in] | node | The node handle from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
Definition at line 210 of file node_utils.hpp.
|
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).
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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. |
[in] | node | The node handle from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
Definition at line 110 of file node_utils.hpp.
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.
[in] | node | The node handle from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
Definition at line 232 of file node_utils.hpp.
|
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).
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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. |
[in] | node | The node handle from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
Definition at line 139 of file node_utils.hpp.
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.
[in] | param | The parameter adapter from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
[in] | logger | The LogHelper used for printing messages. If nullptr, no messages are printed. |
Definition at line 392 of file param_utils.hpp.
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.
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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. |
[in] | param | The parameter adapter from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
[in] | logger | The LogHelper used for printing messages. If nullptr, no messages are printed. |
Definition at line 95 of file param_utils.hpp.
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.
[in] | param | The parameter adapter from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
[in] | logger | The LogHelper used for printing messages. If nullptr, no messages are printed. |
Definition at line 417 of file param_utils.hpp.
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).
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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. |
[in] | param | The parameter adapter from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
[in] | logger | The LogHelper used for printing messages. If nullptr, no messages are printed. |
Definition at line 304 of file param_utils.hpp.
|
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.
[in] | node | The node handle from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
Definition at line 165 of file node_utils.hpp.
|
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).
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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. |
[in] | node | The node handle from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. If std::nullopt, then the parameter is required. If a required param is not found, a GetParamException is thrown. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
Definition at line 51 of file node_utils.hpp.
|
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.
[in] | node | The node handle from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
Definition at line 187 of file node_utils.hpp.
|
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).
ResultType | Param type (the C++ type). It is converted from the intermediate ParamServerType using options.toResult function (which defaults to static_cast). |
ParamServerType | Intermediate 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. |
[in] | node | The node handle from which parameters are read. |
[in] | name | Name of the parameter. |
[in] | defaultValue | The default value to use. |
[in] | unit | Optional string serving as a [physical/SI] unit of the parameter, just to make the messages more informative. |
[in] | options | Options specifying detailed behavior of this function. Use the braced initializer syntax for comfortable writing, e.g. {.throwIfConvertFails = true, .allowNestedParams = false} . |
Definition at line 80 of file node_utils.hpp.
double cras::getPitch | ( | const ::geometry_msgs::Quaternion & | quat | ) |
Get pitch from the given quaternion.
[in] | quat | The quaternion to convert. |
double cras::getPitch | ( | const ::tf2::Quaternion & | quat | ) |
Get pitch from the given quaternion.
[in] | quat | The quaternion to convert. |
double cras::getRoll | ( | const ::geometry_msgs::Quaternion & | quat | ) |
Get roll from the given quaternion.
[in] | quat | The quaternion to convert. |
double cras::getRoll | ( | const ::tf2::Quaternion & | quat | ) |
Get roll from the given quaternion.
[in] | quat | The quaternion to convert. |
void cras::getRPY | ( | const ::geometry_msgs::Quaternion & | quat, |
double & | roll, | ||
double & | pitch, | ||
double & | yaw | ||
) |
Get roll, pitch and yaw from the given quaternion.
[in] | quat | The quaternion to convert. |
[out] | roll | Roll in radians. |
[out] | pitch | Pitch in radians. |
[out] | yaw | Yaw in radians. |
void cras::getRPY | ( | const ::tf2::Quaternion & | quat, |
double & | roll, | ||
double & | pitch, | ||
double & | yaw | ||
) |
Get roll, pitch and yaw from the given quaternion.
[in] | quat | The quaternion to convert. |
[out] | roll | Roll in radians. |
[out] | pitch | Pitch in radians. |
[out] | yaw | Yaw in radians. |
std::string cras::getThreadName | ( | ) |
Get the OS name of the current thread.
inline ::std::string cras::getTypeName | ( | ) |
Get a human-readable name of T.
T | Type to get info about. |
Definition at line 41 of file type_utils.hpp.
::std::string cras::getTypeName | ( | const ::std::type_info & | typeInfo | ) |
Get a human-readable name of a type represented by the given typeinfo.
[in] | typeInfo | Info about the type. |
double cras::getYaw | ( | const ::geometry_msgs::Quaternion & | quat | ) |
Get yaw from the given quaternion.
[in] | quat | The quaternion to convert. |
double cras::getYaw | ( | const ::tf2::Quaternion & | quat | ) |
Get yaw from the given quaternion.
[in] | quat | The quaternion to convert. |
bool cras::hasField | ( | const ::cras::Cloud & | cloud, |
const ::std::string & | fieldName | ||
) |
Return true if the cloud contains a field with the given name.
[in] | cloud | The cloud to search. |
[in] | fieldName | Name of the field. |
::std::string cras::iconvConvert | ( | const ::std::string & | toEncoding, |
const ::std::string & | fromEncoding, | ||
const ::std::string & | inText, | ||
bool | translit = false , |
||
bool | ignore = false , |
||
double | initialOutbufSizeScale = 1.0 , |
||
double | outbufEnlargeCoef = 2.0 , |
||
const ::cras::optional<::std::string > & | localeName = ::cras::nullopt |
||
) |
Convert inText
from fromEncoding
to toEncoding
using iconv.
toEncoding | The target encoding. It may contain the //TRANSLIT and //IGNORE suffixes. |
fromEncoding | The source encoding. |
inText | The text to convert. |
translit | If true, the conversion will try to transliterate letters not present in target encoding. |
ignore | If true, letters that can't be converted and transliterated will be left out. |
initialOutbufSizeScale | The initial scale of the size of the output buffer. Setting this to the correct value may speed up the conversion in case the output is much larger than the input. |
outbufEnlargeCoef | The step size to use for enlarging the output buffer if it shows that its initial size is insufficient. Must be strictly larger than 1.0. |
localeName | If set, specifies the locale used for the iconv call. It may influence the transliteration results. If not set, a default english locale is used that usually works quite well. |
bool cras::isLegalBaseName | ( | const ::std::string & | name | ) |
Validates that name is a legal base name for a graph resource. A base name has no namespace context, e.g. "node_name".
name | Name |
bool cras::isLegalName | ( | const ::std::string & | name | ) |
Check if name is a legal ROS name for graph resources.
name | Name |
bool cras::isNodeletUnloading | ( | const ::nodelet::Nodelet & | nodelet | ) |
Tells whether the nodelet is currently being unloaded (with some pending callbacks still running).
[in] | nodelet | The nodelet to check. |
bool cras::isSetIntersectionEmpty | ( | const ::std::set< T > & | set1, |
const ::std::set< T > & | set2 | ||
) |
Test whether the two given sets have empty intersection.
T | Type of the elements in the sets. |
[in] | set1 | First set to test. |
[in] | set2 | Second set to test. |
Definition at line 26 of file set_utils.hpp.
::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
.
T | An iterable type (must support size() and foreach). |
[in] | strings | The elements to put into a string. |
[in] | delimiter | Delimiter put between elements. |
Definition at line 496 of file string_utils.hpp.
int8_t cras::logLevelToRosgraphMsgLevel | ( | ::ros::console::Level | rosLevel | ) |
Convert the given rosconsole logging level to rosgraph_msgs::Log
level constant.
[in] | rosLevel | The rosconsole logging level. |
rosgraph_msgs::Log
level constant. ::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).
T | Type of the object to allocate. |
Args | Constructor argument types. |
[in] | args | Constructor arguments. |
msg = cras::make_shared_from_fast_pool<sensor_msgs::PointCloud2>();
Definition at line 32 of file pool_allocator.hpp.
::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).
T | Type of the object to allocate. |
Args | Constructor argument types. |
[in] | args | Constructor arguments. |
msg = cras::make_shared_from_pool<sensor_msgs::PointCloud2>();
Definition at line 49 of file pool_allocator.hpp.
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.
[in] | node | The node to bind to. |
[in] | ns | If nonempty, returns just the parameters in the given namespace. |
Definition at line 248 of file node_utils.hpp.
::ros::Time cras::nowFallbackToWall | ( | ) |
Return current ROS time if it has already been initialized, or current wall time.
|
inline |
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.
[in] | allocator | The allocator to use. |
[in] | bytes | The bytes to copy into the allocated buffer. |
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.
[in] | allocator | The allocator to use. |
[in] | bytes | The bytes to copy into the allocated buffer. |
[in] | length | Length of bytes . |
uint8_t* cras::outputRosMessage | ( | allocator_t | allocator, |
const Message & | msg | ||
) |
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).
[in] | allocator | The allocator to use. |
[in] | string | The zero-terminated string to copy into the allocated buffer. |
[in] | length | Length of the string to copy including the null termination character. |
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).
[in] | allocator | The allocator to use. |
[in] | string | The string to copy into the allocated buffer. |
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.
[in] | node | The node to bind to. |
Definition at line 264 of file node_utils.hpp.
double cras::parseDouble | ( | const ::std::string & | string | ) |
Parse the given string to a double.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a double value or if there are excess characters other than whitespace. |
|
inline |
Parse the given string to a double.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a double value or if there are excess characters other than whitespace. |
Definition at line 936 of file string_utils.hpp.
D cras::parseDuration | ( | const ::std::string & | s | ) |
Parse the given string as duration.
This function accepts this general format:
[{-|+}][HH:]MM:SS[.m]
However, many modifications of the format are supported:
:-/_
(or empty string) and it doesn't need to be consistent in the string.,
can be used instead of decimal dot .
.[in] | s | The string to parse. |
std::invalid_argument | If the string does not represent a duration. |
float cras::parseFloat | ( | const ::std::string & | string | ) |
Parse the given string to a float.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a float value or if there are excess characters other than whitespace. |
|
inline |
Parse the given string to a float.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a float value or if there are excess characters other than whitespace. |
Definition at line 915 of file string_utils.hpp.
|
inline |
Parse the given string to a 16-bit int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 16-bit int value or if there are excess characters other than whitespace. |
Definition at line 640 of file string_utils.hpp.
|
inline |
Parse the given string to a 16-bit int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 16-bit int value or if there are excess characters other than whitespace. |
Definition at line 654 of file string_utils.hpp.
int16_t cras::parseInt16 | ( | const std::string & | string | ) |
Parse the given string to a 16-bit int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 16-bit int value or if there are excess characters other than whitespace. |
int16_t cras::parseInt16 | ( | const std::string & | string, |
uint8_t | base | ||
) |
Parse the given string to a 16-bit int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 16-bit int value or if there are excess characters other than whitespace. |
|
inline |
Parse the given string to a 32-bit int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 32-bit int value or if there are excess characters other than whitespace. |
Definition at line 736 of file string_utils.hpp.
|
inline |
Parse the given string to a 32-bit int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 32-bit int value or if there are excess characters other than whitespace. |
Definition at line 750 of file string_utils.hpp.
int32_t cras::parseInt32 | ( | const std::string & | string | ) |
Parse the given string to a 32-bit int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 32-bit int value or if there are excess characters other than whitespace. |
int32_t cras::parseInt32 | ( | const std::string & | string, |
uint8_t | base | ||
) |
Parse the given string to a 32-bit int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 32-bit int value or if there are excess characters other than whitespace. |
|
inline |
Parse the given string to a 64-bit int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 64-bit int value or if there are excess characters other than whitespace. |
Definition at line 832 of file string_utils.hpp.
|
inline |
Parse the given string to a 64-bit int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 64-bit int value or if there are excess characters other than whitespace. |
Definition at line 846 of file string_utils.hpp.
int64_t cras::parseInt64 | ( | const std::string & | string | ) |
Parse the given string to a 64-bit int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 64-bit int value or if there are excess characters other than whitespace. |
int64_t cras::parseInt64 | ( | const std::string & | string, |
uint8_t | base | ||
) |
Parse the given string to a 64-bit int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 64-bit int value or if there are excess characters other than whitespace. |
|
inline |
Parse the given string to a 8-bit int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 8-bit int value or if there are excess characters other than whitespace. |
Definition at line 544 of file string_utils.hpp.
|
inline |
Parse the given string to a 8-bit int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 8-bit int value or if there are excess characters other than whitespace. |
Definition at line 558 of file string_utils.hpp.
int8_t cras::parseInt8 | ( | const std::string & | string | ) |
Parse the given string to a 8-bit int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 8-bit int value or if there are excess characters other than whitespace. |
int8_t cras::parseInt8 | ( | const std::string & | string, |
uint8_t | base | ||
) |
Parse the given string to a 8-bit int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 8-bit int value or if there are excess characters other than whitespace. |
T cras::parseTime | ( | const ::std::string & | s, |
const ::cras::optional< typename ::cras::DurationType< T >::value > & | timezoneOffset = {} , |
||
const T & | referenceDate = {} |
||
) |
Parse the given string as time.
This function accepts this general format:
[[YY]YY:MM:DD ]HH:MM:SS[.m][{Z|{+|-}HH[:]MM}]
However, many modifications of the format are supported:
:-/_
(or empty string) and it doesn't need to be consistent in the string.Tt_-
.referenceTime
.20YY
is assumed.timezoneOffset
. But if the string contains a TZ offset, it will be used instead the one passed as argument. If neither is specified, UTC is assumed.now
is recognized and always returns current time. It can be any case (NOW
, Now
etc.).,
can be used instead of decimal dot .
.[in] | s | The string to parse. |
[in] | timezoneOffset | Optional timezone offset to use if no offset is specified in the string. |
[in] | referenceDate | If the date part is missing in the string, the date from this argument will be used. |
std::invalid_argument | If the string does not represent a date with time. |
D cras::parseTimezoneOffset | ( | const ::std::string & | s | ) |
Parse timezone offset from the given string.
This function accepts this format:
{|Z|[{+|-}HH[:]MM]}
D | Duration type. |
[in] | s | The string to parse. |
|
inline |
Parse the given string to a 16-bit unsigned int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 16-bit uint value or if there are excess characters other than whitespace. |
Definition at line 688 of file string_utils.hpp.
|
inline |
Parse the given string to a 16-bit unsigned int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 16-bit uint value or if there are excess characters other than whitespace. |
Definition at line 702 of file string_utils.hpp.
uint16_t cras::parseUInt16 | ( | const std::string & | string | ) |
Parse the given string to a 16-bit unsigned int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 16-bit uint value or if there are excess characters other than whitespace. |
uint16_t cras::parseUInt16 | ( | const std::string & | string, |
uint8_t | base | ||
) |
Parse the given string to a 16-bit unsigned int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 16-bit uint value or if there are excess characters other than whitespace. |
|
inline |
Parse the given string to a 32-bit unsigned int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 32-bit uint value or if there are excess characters other than whitespace. |
Definition at line 784 of file string_utils.hpp.
|
inline |
Parse the given string to a 32-bit unsigned int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 32-bit uint value or if there are excess characters other than whitespace. |
Definition at line 798 of file string_utils.hpp.
uint32_t cras::parseUInt32 | ( | const std::string & | string | ) |
Parse the given string to a 32-bit unsigned int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 32-bit uint value or if there are excess characters other than whitespace. |
uint32_t cras::parseUInt32 | ( | const std::string & | string, |
uint8_t | base | ||
) |
Parse the given string to a 32-bit unsigned int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 32-bit uint value or if there are excess characters other than whitespace. |
|
inline |
Parse the given string to a 64-bit unsigned int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 64-bit uint value or if there are excess characters other than whitespace. |
Definition at line 880 of file string_utils.hpp.
|
inline |
Parse the given string to a 64-bit unsigned int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 64-bit uint value or if there are excess characters other than whitespace. |
Definition at line 894 of file string_utils.hpp.
uint64_t cras::parseUInt64 | ( | const std::string & | string | ) |
Parse the given string to a 64-bit unsigned int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 64-bit uint value or if there are excess characters other than whitespace. |
uint64_t cras::parseUInt64 | ( | const std::string & | string, |
uint8_t | base | ||
) |
Parse the given string to a 64-bit unsigned int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 64-bit uint value or if there are excess characters other than whitespace. |
|
inline |
Parse the given string to a 8-bit unsigned int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 8-bit uint value or if there are excess characters other than whitespace. |
Definition at line 592 of file string_utils.hpp.
|
inline |
Parse the given string to a 8-bit unsigned int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 8-bit uint value or if there are excess characters other than whitespace. |
Definition at line 606 of file string_utils.hpp.
uint8_t cras::parseUInt8 | ( | const std::string & | string | ) |
Parse the given string to a 8-bit unsigned int.
[in] | string | The string to parse. |
std::invalid_argument | If the string does not represent a 8-bit uint value or if there are excess characters other than whitespace. |
uint8_t cras::parseUInt8 | ( | const std::string & | string, |
uint8_t | base | ||
) |
Parse the given string to a 8-bit unsigned int.
[in] | string | The string to parse. |
[in] | base | The numerical base (radix). |
std::invalid_argument | If the string does not represent a 8-bit uint value or if there are excess characters other than whitespace. |
::std::string cras::prependIfNonEmpty | ( | const ::std::string & | str, |
const ::std::string & | prefix | ||
) |
If str
is nonempty, returns prefix + str, otherwise empty string.
[in] | str | The main string. |
[in] | prefix | The string's prefix. |
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*).
T | The type to check. |
[in] | s | The input string. |
s
in double quotes if T
is a string type, or just s
. Definition at line 307 of file string_utils.hpp.
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.
[in] | channelPrefix | Prefix of the channel. E.g. normal_ for registering type of normal_x,normal_y,normal_z. |
[in] | type | Type of the channel. |
::ros::Duration cras::remainingTime | ( | const ::ros::Time & | query, |
const ::ros::Duration & | timeout | ||
) |
Return remaining time to timeout from the query time.
[in] | query | The query time, e.g. of a TF. |
[in] | timeout | Maximum time to wait from the query time onwards. |
::ros::Duration cras::remainingTime | ( | const ::ros::Time & | query, |
double | timeout | ||
) |
Return remaining time to timeout from the query time.
[in] | query | The query time, e.g. of a TF. |
[in] | timeout | Maximum time to wait from the query time onwards. |
::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.
[in] | str | The string to work on. |
[in] | prefix | The prefix to find. |
[in] | hadPrefix | If non-null, will contain information whether str starts with prefix . |
str
starts with prefix
, it will return str
with prefix
removed. Otherwise, str
will be returned unchanged. ::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.
[in] | str | The string to work on. |
[in] | suffix | The suffix to find. |
[in] | hadSuffix | If non-null, will contain information whether str ends with suffix . |
str
ends with suffix
, it will return str
with suffix
removed. Otherwise, str
will be returned unchanged. 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
.
[in,out] | str | The string to replace in. |
[in] | from | The string to replace. |
[in] | to | The replacement. |
[in] | where | Where to do the replacement. |
::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
.
[in] | str | The string to replace in. |
[in] | from | The string to replace. |
[in] | to | The replacement. |
[in] | where | Where to do the replacement. |
str
with all occurrences of from
replaced with to
. ::ros::console::Level cras::rosgraphMsgLevelToLogLevel | ( | uint8_t | msgLevel | ) |
Convert the given rosgraph_msgs::Log
level constant to rosconsole logging level.
[in] | msgLevel | A rosgraph_msgs::Log level constant. |
::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.
[in] | frequency | The frequency to convert. |
::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.
[in] | frequency | The frequency to convert. |
::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.
[in] | time | The time to be added to. |
[in] | duration | The duration to add. |
::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.
[in] | time | The time to be added to. |
[in] | duration | The duration to add. |
::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.
[in] | time | The time to be added to. |
[in] | duration | The duration to add. |
void cras::setThreadName | ( | const std::string & | name | ) |
Set the OS name of the current thread.
[in] | name | The name to set. |
size_t cras::sizeOfPointField | ( | const ::sensor_msgs::PointField & | field | ) |
Return the size (in bytes) of the data represented by the sensor_msgs::PointField.
[in] | field | The pointfield specification. |
std::runtime_error | if wrong datatype is passed. |
size_t cras::sizeOfPointField | ( | int | datatype | ) |
Return the size (in bytes) of a sensor_msgs::PointField datatype.
[in] | datatype | The datatype (one of sensor_msgs::PointField::(U?INT(8|16|32)|FLOAT(32|64)) constants). |
std::runtime_error | if wrong datatype is passed. |
::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.
[in] | str | The string to split. |
[in] | delimiter | The delimiter used for splitting. |
[in] | maxSplits | If >= 0, defines the maximum number of splits. |
bool cras::startsWith | ( | const ::std::string & | str, |
const ::std::string & | prefix | ||
) |
Check whether prefix
is a prefix of str
.
[in] | str | The string to be searched in. |
[in] | prefix | The string to be found in str . |
prefix
is a prefix of str
. void cras::strip | ( | ::std::string & | s, |
const char & | c = ' ' |
||
) |
Strip c
from the beginning and end of the given string (if it is there).
[in,out] | s | The string from which c should be removed. |
[in] | c | The character to remove. |
::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).
[in] | s | The string from which c should be removed. |
[in] | c | The character to remove. |
void cras::stripLeading | ( | ::std::string & | s, |
const char & | c = ' ' |
||
) |
Strip c
from the start of the given string (if there is one).
[in,out] | s | The string from which c should be removed. |
[in] | c | The character to remove. |
::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).
[in] | s | The string from which c should be removed. |
[in] | c | The character to remove. |
void cras::stripLeadingSlash | ( | ::std::string & | s, |
bool | warn = false |
||
) |
Strip leading slash from the given string (if there is one).
[in,out] | s | The string from which slash should be removed. |
[in] | warn | If true, issue a ROS warning if the string contained the leading slash. |
::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).
[in] | s | The string from which slash should be removed. |
[in] | warn | If true, issue a ROS warning if the string contained the leading slash. |
void cras::stripTrailing | ( | ::std::string & | s, |
const char & | c = ' ' |
||
) |
Strip c
from the end of the given string (if there is one).
[in,out] | s | The string from which c should be removed. |
[in] | c | The character to remove. |
::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).
[in] | s | The string from which c should be removed. |
[in] | c | The character to remove. |
|
constexpr |
Return a string representation of the XmlRpcValue type.
[in] | value | The value to get type of. |
Definition at line 33 of file xmlrpc_value_traits.hpp.
inline ::std::string cras::to_string | ( | char * | value | ) |
Definition at line 371 of file string_utils.hpp.
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.
inline ::std::string cras::to_string | ( | const ::Eigen::RotationBase< Derived, Dim > & | value | ) |
Definition at line 29 of file string_utils/eigen.hpp.
inline ::std::string cras::to_string | ( | const ::Eigen::Transform< Scalar, Dim, Mode, Options > & | value | ) |
Definition at line 37 of file string_utils/eigen.hpp.
inline ::std::string cras::to_string | ( | const ::std::array< T, N > & | value | ) |
Definition at line 450 of file string_utils.hpp.
inline ::std::string cras::to_string | ( | const ::std::map< K, V > & | value | ) |
inline ::std::string cras::to_string | ( | const ::std::string & | value | ) |
Definition at line 393 of file string_utils.hpp.
inline ::std::string cras::to_string | ( | const ::std::unordered_map< K, V > & | value | ) |
inline ::std::string cras::to_string | ( | const ::tf2::Matrix3x3 & | value | ) |
Definition at line 36 of file string_utils/tf2.hpp.
inline ::std::string cras::to_string | ( | const ::tf2::Quaternion & | value | ) |
Definition at line 26 of file string_utils/tf2.hpp.
inline ::std::string cras::to_string | ( | const ::tf2::Transform & | value | ) |
Definition at line 44 of file string_utils/tf2.hpp.
inline ::std::string cras::to_string | ( | const ::tf2::Vector3 & | value | ) |
Definition at line 21 of file string_utils/tf2.hpp.
inline ::std::string cras::to_string | ( | const ::XmlRpc::XmlRpcValue & | value | ) |
Definition at line 18 of file xmlrpc.hpp.
inline ::std::string cras::to_string | ( | const ::XmlRpc::XmlRpcValue::Type & | value | ) |
Definition at line 60 of file xmlrpc_value_traits.hpp.
inline ::std::string cras::to_string | ( | const bool & | value | ) |
Definition at line 388 of file string_utils.hpp.
inline ::std::string cras::to_string | ( | const char * | value | ) |
Definition at line 366 of file string_utils.hpp.
inline ::std::string cras::to_string | ( | const char | value[I] | ) |
Definition at line 377 of file string_utils.hpp.
inline ::std::string cras::to_string | ( | const double & | value | ) |
Definition at line 351 of file string_utils.hpp.
inline ::std::string cras::to_string | ( | const float & | value | ) |
Definition at line 356 of file string_utils.hpp.
inline ::std::string cras::to_string | ( | const long double & | value | ) |
Definition at line 361 of file string_utils.hpp.
|
inline |
Definition at line 54 of file string_utils/ros.hpp.
inline ::std::string cras::to_string | ( | const T & | value | ) |
Definition at line 35 of file string_utils/ros.hpp.
|
inline |
Convert the given value to a string representation.
T | Type of the value. |
[in] | value | The value to convert. |
Definition at line 331 of file string_utils.hpp.
|
inline |
Convert the given value to a string representation.
T | Type of the value. |
[in] | value | The value to convert. |
Definition at line 343 of file string_utils.hpp.
::Eigen::Isometry3d cras::toEigen | ( | const ::urdf::Pose & | pose | ) |
::Eigen::Quaterniond cras::toEigen | ( | const ::urdf::Rotation & | rotation | ) |
::Eigen::Translation3d cras::toEigen | ( | const ::urdf::Vector3 & | position | ) |
::std::string cras::toLower | ( | const ::std::string & | str | ) |
Convert all characters in the given string to lower case.
[in] | str | The input string. |
::std::string cras::toUpper | ( | const ::std::string & | str | ) |
Convert all characters in the given string to upper case.
[in] | str | The input string. |
::urdf::Pose cras::toURDF | ( | const ::Eigen::Isometry3d & | pose | ) |
Convert Eigen isometry to URDF Pose.
[in] | pose | The pose to convert. |
::urdf::Rotation cras::toURDF | ( | const ::Eigen::Quaterniond & | rotation | ) |
Convert Eigen quaternion to URDF Rotation.
[in] | rotation | The quaternion to convert. |
::urdf::Vector3 cras::toURDF | ( | const ::Eigen::Translation3d & | translation | ) |
Convert Eigen translation to URDF Vector3.
[in] | translation | The translation to convert. |
::urdf::Vector3 cras::toURDF | ( | const ::Eigen::Vector3d & | vector | ) |
Convert Eigen vector to URDF Vector3.
[in] | vector | The vector to convert. |
::std::string cras::toValidRosName | ( | const ::std::string & | text, |
bool | baseName = true , |
||
const ::cras::optional<::std::string > & | fallbackName = ::cras::nullopt |
||
) |
Make sure the given string can be used as ROS name.
text | The text to convert. |
baseName | If true, the text represents only one "level" of names. If False, it can be the absolute or relative name with ~ and /. |
fallbackName | If specified, this name will be used if the automated conversion fails. This name is not checked to be valid. |
std::invalid_argument | If the given text cannot be converted to a valid ROS name, and no fallback_name is specified. |
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.
[in,out] | cloud | The cloud. |
[in] | transform | The transform to apply. |
[in] | channelPrefix | Prefix of the channel. |
[in] | type | Type of the channel. |
::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.
[in] | in | The input cloud. |
[out] | out | The output cloud (can not be the same as input). |
[in] | tf | The transform to apply. |
[in] | channels | A map of channel prefix -channel type of channels that should be transformed. No other channels will be present in the output cloud. |
out
. ::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.
[in] | in | The input cloud. |
[out] | out | The output cloud (can not be the same as input). |
[in] | tf | The transform to apply. |
out
. ::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().
[in] | in | The input cloud. |
[out] | out | The output cloud (can be the same as input). |
[in] | tf | The transform to apply. |
out
. ::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.
[in] | in | The input cloud. |
[out] | out | The output cloud (can be the same as input). |
[in] | tf | The transform to apply. |
[in] | channels | A map of channel prefix -channel type of channels that should be transformed. |
out
. ::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().
[in] | in | The input cloud. |
[out] | out | The output cloud (can be the same as input). |
[in] | tfBuffer | The TF buffer. |
[in] | targetFrame | The frame to transform to. |
out
. tf2::TransformException | No exceptions thrown from lookupTransform() will be catched. |
::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.
[in] | in | The input cloud. |
[out] | out | The output cloud (can be the same as input). |
[in] | tfBuffer | The TF buffer. |
[in] | targetFrame | The frame to transform to. |
[in] | channels | A map of channel prefix -channel type of channels that should be transformed. |
out
. tf2::TransformException | No exceptions thrown from lookupTransform() will be catched. |
::std::string cras::transliterateToAscii | ( | const ::std::string & | text | ) |
Transliterate the given string from UTF-8 to ASCII (replace non-ASCII chars by closest ASCII chars).
text | The string to transliterate. |
void cras::unregisterCloudChannelType | ( | const ::std::string & | channelPrefix | ) |
Unregister a cloud channel type registered earlier with registerCloudChannelType().
[in] | channelPrefix | Prefix of the channel. |
LONG_MAX USHRT_MAX cras::int |
Definition at line 125 of file xmlrpc_value_utils.hpp.
cras::LONG_MIN |
Definition at line 125 of file xmlrpc_value_utils.hpp.
const ParamHelper cras::paramHelper(::std::make_shared<::cras::NodeLogHelper >()) |
Static variable that serves as the singleton for getting node parameters.