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

Namespaces

 impl
 
 priority_mux
 

Classes

class  BoundParamHelper
 
class  ChangeHeaderNodelet
 Nodelet for relaying messages and changing their header. More...
 
class  ConditionalSubscriber
 A lazy subscriber that subscribes only when a condition is met. More...
 
class  CountMessagesNodelet
 Nodelet for counting messages and their size. More...
 
struct  DefaultParamServerType
 
struct  DefaultToParamFn
 
struct  DefaultToResultFn
 
class  DiagnosedPublisher
 
class  DiagnosedPubSub
 
class  DiagnosedSubscriber
 
class  DiagnosticUpdater
 
class  DurationStatus
 
struct  DurationStatusParam
 
class  FilterBase
 
class  FilterChain
 
class  FilterChainDiagnostics
 
class  FilterChainNodelet
 
struct  FilterGetParamAdapter
 
class  FilterLogHelper
 
class  FrequencyStatusParam
 
struct  from_chars_result
 
class  GenericLazyPubSub
 A pair of lazy subscriber and publisher which use the same message type (unknown at compile time). More...
 
struct  GetParamAdapter
 
class  GetParamException
 
struct  GetParamOptions
 
struct  GetParamResult
 
struct  GetParamResultInfo
 
class  HasLogger
 
class  HeartbeatNodelet
 Nodelet that republishes heartbeat of a topic with header. More...
 
struct  InterruptibleSleepInterface
 
class  InterruptibleTFBuffer
 
struct  is_any
 
struct  is_any<::cras::any >
 
struct  is_c_string
 
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
 
struct  is_cras_expected<::cras::expected< T, E > >
 
struct  is_optional
 
struct  is_optional<::cras::optional< T > >
 
struct  is_string
 
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  LazySubscriber
 Lazy subscriber that subscribes only when a paired publisher has subscribers. More...
 
class  LazySubscriberBase
 Base for lazy subscribers that subscribes only when a paired publisher has subscribers. More...
 
class  LoaderROS
 
class  LogHelper
 
class  MemoryLogHelper
 
class  NodeHandle
 
struct  NodeHandleGetParamAdapter
 
class  NodeHandleWithDiagnostics
 
class  Nodelet
 
class  NodeletAwareTFBuffer
 
class  NodeletBase
 
class  NodeletLogHelper
 
class  NodeletManager
 
class  NodeletManagerSharingTfBuffer
 
class  NodeletParamHelper
 
struct  NodeletWithDiagnostics
 
struct  NodeletWithSharedTfBuffer
 
struct  NodeletWithSharedTfBufferInterface
 
class  NodeLogHelper
 
class  NodeParamHelper
 
class  ParamHelper
 
struct  ParamToStringFn
 
class  PriorityMux
 A class for priority-based muxing of topics. More...
 
class  PriorityMuxNodelet
 Priority-based muxer nodelet for topics. More...
 
class  RateLimiter
 
class  RelayNodelet
 Nodelet for relaying messages on a different topic. More...
 
class  RepeatMessagesNodelet
 Nodelet for repeating messages coming at a slower rate (or even just a single message). More...
 
class  Resettable
 
class  ReverseSemaphore
 
class  RosconsoleLogHelper
 
class  RunningStats
 
class  SemaphoreGuard
 
class  ShapeShifter
 ShapeShifter class with fixed behavior on copy/move on Melodic. Use this class everywhere possible to prevent memory corruption. It seamlessly converts to topic_tools::ShapeShifter; More...
 
struct  SimpleDurationStatusParam
 
struct  SimpleTopicStatusParamNoHeader
 
struct  SimpleTopicStatusParamWithHeader
 
class  StatefulNodelet
 
struct  StatefulNodeletInterface
 
class  ThreadNameUpdatingNodelet
 
class  ThrottleLimiter
 
class  ThrottleMessagesNodelet
 Nodelet for throttling messages on a topic. More...
 
class  TimeJumpResettable
 
class  TokenBucketLimiter
 
class  TopicStatus
 
struct  TopicStatusParams
 
class  TopicStatusParamWithHeader
 
class  WrapperLogHelper
 
struct  XmlRpcValueGetParamAdapter
 
struct  XmlRpcValueTraits
 
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)
 
typedef typename ::ros::ParameterAdapter< M >::Message BaseMessage
 
typedef ::std::shared_ptr<::cras::BoundParamHelperBoundParamHelperPtr
 
typedef typename std::enable_if_t< !::cras::is_optional< ResultType >::value &&!::cras::is_c_string< ResultType >::value &&!::cras::is_c_string< ParamServerType >::value > check_get_param_types
 
typedef ::sensor_msgs::PointCloud2 Cloud
 
typedef ::sensor_msgs::PointCloud2ConstIterator< float > CloudConstIter
 
typedef ::sensor_msgs::PointCloud2ConstIterator< intCloudIndexConstIter
 
typedef ::sensor_msgs::PointCloud2Iterator< intCloudIndexIter
 
typedef ::sensor_msgs::PointCloud2Iterator< float > CloudIter
 
typedef ::sensor_msgs::PointCloud2Modifier CloudModifier
 
typedef ::std::shared_ptr<::cras::DurationStatusDurationStatusPtr
 
typedef ::cras::impl::GenericCloudConstIterator GenericCloudConstIter
 
typedef ::cras::impl::GenericCloudIterator GenericCloudIter
 
typedef ::std::shared_ptr<::cras::GetParamAdapterGetParamAdapterPtr
 
typedef ::ros::message_traits::IsMessage<::cras::BaseMessage< M > > IsMessageParam
 
typedef ::cras::LogHelper::ConstPtr LogHelperConstPtr
 
typedef ::cras::LogHelper::Ptr LogHelperPtr
 
typedef ::std::shared_ptr<::cras::ParamHelperParamHelperPtr
 
typedef ::std::conditional_t<::ros::message_traits::HasHeader< Message >::value, ::cras::SimpleTopicStatusParamWithHeader, ::cras::SimpleTopicStatusParamNoHeaderSimpleTopicStatusParam
 
typedef ::std::conditional_t<::ros::message_traits::HasHeader< Message >::value, ::cras::TopicStatusParamWithHeader, ::cras::FrequencyStatusParamTopicStatusParam
 
typedef ::std::shared_ptr<::cras::TopicStatus< Message > > TopicStatusPtr
 
typedef ::std::function<::std::string(const T &)> ToStringFn
 

Enumerations

enum  chars_format
 
enum  CloudChannelType { CloudChannelType::POINT, CloudChannelType::DIRECTION, CloudChannelType::SCALAR }
 
enum  ReplacePosition { ReplacePosition::EVERYWHERE, ReplacePosition::START, ReplacePosition::END }
 

Functions

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

Variables

constexpr auto DEFAULT_NONE_TOPIC = "__none"
 
constexpr auto DEFAULT_OUT_TOPIC = "mux_out"
 
 fixed
 
 general
 
 hex
 
 int
 
 LONG_MIN
 
const ParamHelper paramHelper (::std::make_shared<::cras::NodeLogHelper >())
 
 scientific
 

Function Documentation

◆ copyShapeShifter() [1/2]

void cras::copyShapeShifter ( const ::topic_tools::ShapeShifter in,
::topic_tools::ShapeShifter out 
)

Copy in ShapeShifter to out.

Parameters
[in]inInput message.
[in]outOutput message.
Note
This is a workaround for https://github.com/ros/ros_comm/pull/1722 which has not been merged into Melodic.

◆ copyShapeShifter() [2/2]

void cras::copyShapeShifter ( const topic_tools::ShapeShifter in,
topic_tools::ShapeShifter out 
)

Definition at line 93 of file shape_shifter.cpp.

◆ getBuffer() [1/4]

uint8_t* cras::getBuffer ( ::topic_tools::ShapeShifter msg)

Get the internal buffer with serialized message data.

Parameters
[in]msgThe shape shifter object.
Returns
The internal buffer.
Note
The buffer can stop being valid after a ShapeShifter::read() operation or when the shifter is destroyed.

◆ getBuffer() [2/4]

const uint8_t* cras::getBuffer ( const ::topic_tools::ShapeShifter msg)

Get the internal buffer with serialized message data.

Parameters
[in]msgThe shape shifter object.
Returns
The internal buffer.
Note
The buffer can stop being valid after a ShapeShifter::read() operation or when the shifter is destroyed.

◆ getBuffer() [3/4]

const uint8_t* cras::getBuffer ( const topic_tools::ShapeShifter msg)

Definition at line 67 of file shape_shifter.cpp.

◆ getBuffer() [4/4]

uint8_t* cras::getBuffer ( topic_tools::ShapeShifter msg)

Definition at line 62 of file shape_shifter.cpp.

◆ getBufferLength() [1/2]

size_t cras::getBufferLength ( const ::topic_tools::ShapeShifter msg)

Get the length of the internal buffer with serialized message data.

Parameters
[in]msgThe shape shifter object.
Returns
The internal buffer length.
Note
The buffer can stop being valid after a ShapeShifter::read() operation or when the shifter is destroyed.

◆ getBufferLength() [2/2]

size_t cras::getBufferLength ( const topic_tools::ShapeShifter msg)

Definition at line 103 of file shape_shifter.cpp.

◆ getHeader() [1/2]

::cras::optional<::std_msgs::Header> cras::getHeader ( const ::topic_tools::ShapeShifter msg)

Get the header field of the given message, if it has any.

Parameters
[in]msgThe shape shifter object.
Returns
The header of the represented message. If there is no header, nullopt is returned.
Note
This function can have some "false positives", as it doesn't actually know whether the message has a header or not. There is a high chance that if the message does not have a header, the reading of Header data will fail, but there are corner cases when the message data will be interpretable as a Header. It is advised to check whether the message type has a header via introspection, hasHeader() or some other kind of information.

◆ getHeader() [2/2]

cras::optional<std_msgs::Header> cras::getHeader ( const topic_tools::ShapeShifter msg)

Definition at line 122 of file shape_shifter.cpp.

◆ hasHeader() [1/2]

bool cras::hasHeader ( const ::topic_tools::ShapeShifter msg)

Tell whether the given message has header field.

Parameters
[in]msgThe shape shifter object.
Returns
Whether there is a header field in the message.
Note
This function might be slow. Do not call it on receipt of every message on high-frequency topics.

◆ hasHeader() [2/2]

bool cras::hasHeader ( const topic_tools::ShapeShifter msg)

Definition at line 108 of file shape_shifter.cpp.

◆ msgToShapeShifter()

template<typename T , typename EnableT >
void cras::msgToShapeShifter ( const T &  msg,
::topic_tools::ShapeShifter shifter 
)

Copy the message instance into the given ShapeShifter.

Template Parameters
TType of the message.
Parameters
[in]msgThe message to copy.
[out]shifterThe ShapeShifter to copy to.
Note
All old references to the shifter's internal buffer have to be treated as invalid after calling this function.

Definition at line 22 of file shape_shifter.hpp.

◆ resizeBuffer() [1/2]

void cras::resizeBuffer ( ::topic_tools::ShapeShifter msg,
size_t  newLength 
)

Resize the internal buffer of the message.

Parameters
[in,out]msgThe message to change.
[in]newLengthNew length of the internal buffer.
Note
If the new size is the same as the old one, nothing happens. If the new one is longer, the buffer is reallocated and the contents of the old buffer are copied to it. If the new one is shorter, the contained data are cropped to the new length.
Use this function with care. After calling it, the message object becomes invalid until you fix it.

◆ resizeBuffer() [2/2]

void cras::resizeBuffer ( topic_tools::ShapeShifter msg,
size_t  newLength 
)

Definition at line 72 of file shape_shifter.cpp.

◆ setHeader() [1/2]

bool cras::setHeader ( ::topic_tools::ShapeShifter msg,
::std_msgs::Header header 
)

Change the header field of the given message, if it has any.

Parameters
[in,out]msgThe message to change.
[in]headerThe header to set.
Returns
Whether setting the new header has succeeded. It will fail if either the message does not seem to have a header field, or if some serialization/deserialization error occurs. If the function returns false, the message has to be considered invalid and has to be discarded. The caller should use getHeader() or other information sources to make sure the message type actually does have a header.
Note
This function does not (de)serialize the whole message, it only serializes its header part.
If the new header is shorter or same length as the old one, there is no memory allocation happening.

◆ setHeader() [2/2]

bool cras::setHeader ( topic_tools::ShapeShifter msg,
std_msgs::Header header 
)

Definition at line 139 of file shape_shifter.cpp.

Variable Documentation

◆ DEFAULT_NONE_TOPIC

constexpr auto cras::DEFAULT_NONE_TOPIC = "__none"
constexpr

Definition at line 34 of file priority_mux.cpp.

◆ DEFAULT_OUT_TOPIC

constexpr auto cras::DEFAULT_OUT_TOPIC = "mux_out"
constexpr

Definition at line 33 of file priority_mux.cpp.



cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sat Mar 2 2024 03:47:49