cras_cpp_common package from cras_ros_utils repocamera_throttle cras_bag_tools cras_cpp_common cras_docs_common cras_py_common cras_topic_tools image_transport_codecs tf_static_publisher |
|
Package Summary
Tags | No category tags. |
Version | 2.4.2 |
License | BSD |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/ctu-vras/ros-utils.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-09-05 |
Dev Status | DEVELOPED |
CI status |
|
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Martin Pecka
Authors
- Martin Pecka
cras_cpp_common
A Czech-army knife for ROS code written in C++.
The aim of this package is to provide some missing utility functions to roscpp. Using libraries from this package, you should be able to write more efficient, safer and less error-prone code without much boilerplate. As this package is intended to handle a lot of the boring code for you "behind the scenes", ubiquitous effort was put into unit-testing everything, so that you can rely on the provided code without the usual fear whether it works or not.
This readme shortly introduces the provided libraries. Detailed documentation can be found in the comments in code and in the API docs. Examples of usage can be found in the dependent packages from ros-utils
, and in the unit tests.
Parts of this package were used by team CTU-CRAS-Norlab in DARPA Subterranean Challenge.
Support and Build Status
This package is supported on Melodic and Noetic until their End of Life (and maybe later). It is occasionally tested with non-default GCC versions like Melodic+GCC8 or Noetic+GCC11.
List of provided libraries
-
any
: Provides forward compatibility forstd::any
. -
c_api
: Utilities for writing a C API for your packages. -
cloud
,tf2_sensor_msgs
: Utilities for working with pointclouds (iterators, copying, extracting channels, transforming the clouds). -
diag_utils
: Helpers for easy setup of a diagnosed publisher/subscriber that checks message rate or delay. Configuration of the expected rates/delays is via ROS parameters. -
expected
: Provides forward compatibility forstd::expected
. -
filter_utils
:-
FilterBase
eases access to filter parameters viaparam_utils
. -
FilterChain
class and nodelet improve uponfilters::FilterChain
by adding support for dynamic disabling/enabling of individual filters, diagnostics of the individual filters and possibility to publish the intermediate filtering results.
-
-
functional
: Provides forward compatibility forstd::apply()
,std::invoke()
andstd::bind_front()
. Especiallycras::bind_front()
is super useful for specifying ROS subscriber callbacks, where you just bindthis
to the callback, and the rest of the parameters is automatically handled. -
log_utils
: Unified access to theROS_*
andNODELET_*
logging macros. This is more an internal utility of this package. -
math_utils
:sgn()
signum function, andRunningStats
(computes mean and variance on a stream of data in O(1) time per sample). -
message_utils
:BaseMessage<M>
andIsMessageParam<M>
template helpers for working with ROS message classes. -
node_utils
: Integration ofdiag_utils
andparam_utils
for ROS nodes. -
nodelet_utils
:-
cras::Nodelet
base class provides integration ofdiag_utils
andparam_utils
for nodelets, adds the ability to update name of the current thread with name of the nodelet, adds support for sharing a single TF buffer between multiple nodelets, and provides anok()
method that is similar toros::ok()
, but starts returningfalse
when the nodelet is being unloaded. -
nodelet_manager_sharing_tf_buffer
is a customized nodelet manager that is able to share its own (single) TF buffer to multiple nodelets (based oncras::Nodelet
).
-
-
optional
: Provides forward compatibility forstd::optional
. -
param_utils
: Utilities for type-safe, easy, unified and configurable access to ROS parameters. See below for examples and more details. -
pool_allocator
: Provides a memory-pool-based allocator for ROS messages. It comes handy if you want to publish shared pointer messages on a high rate - it should decrease the time needed for object allocation vianew
. -
rate_limiter
: Library for intelligent rate-limiting of events (mainly messages). So far it implements the algorithm fromtopic_tools throttle
(not very good), and token bucket algorithm (pretty good for most cases). -
set_utils
: ProvidesisSetIntersectionEmpty()
working on a pair ofstd::set
s. -
small_map
: ProvidesSmallMap
andSmallSet
, variants ofstd::map
implemented usingstd::list
which are append-only and lock-free for reading. -
span
: Provides forward compatibility forstd::span
. -
string_utils
: Provides many string manipulation helpers you've always dreamed of. Universalto_string()
that converts almost anything to a sensible string.startsWith()
/endsWith()
,replace()
,contains()
,split()
/join()
,format()
(likesprintf()
but without hassle and onstd::string
),stripLeading()
/stripTrailing()
,removePrefix()
/removeSuffix()
,parseFloat()
/parseDouble()
(convert string to double independent of locale!),parseInt32()
and friends (parse many textual representations to an integer). -
suppress_warnings
: Unified macros that suppress various compiler warnings for a piece of code. -
test_utils
: Provide a hack that allows loading a locally-defined nodelet without the need to register it via package.xml. -
tf2_utils
:getRoll()
,getPitch()
,getYaw()
,getRPY()
from atf2::Quaternion
orgeometry_msgs::Quaternion
!- Also provides
InterruptibleTFBuffer
that can cooperate withcras::Nodelet
and stop a TF lookup if the nodelet is being unloaded (normally, the lookup freezes when you pause simulation time).
- Also provides
-
thread_utils
:getThreadName()
andsetThreadName()
.- Also provides
ReverseSemaphore
synchronization primitive that counts towards zero and notifies when empty.
- Also provides
-
time_utils
:remainingTime()
tells you how much of a timeout remains if you started waiting at some specified time. Conversions betweenros::Rate()
and frequency. Multiplication and division operators for ROS duration types. -
type_utils
: Provides compile-time and run-timegetTypeName()
helper that converts a C++ type to a string containing its name. -
urdf_utils
: Conversions betweenurdf
andEigen
types. -
xmlrpc_value_traits
: Type traits forXmlRpc::XmlRpcValue
. -
xmlrpc_value_utils
: Conversions betweenXmlRpc::XmlRpcValue
and C++ and STL types.
List of provided CMake helpers
-
node_from_nodelet
: Easily convert a nodelet into a standalone node executable. Seecras_topic_tools
package for an example.
param_utils
: Parameter Reading Helpers
param_utils
, node_utils
, nodelet_utils
and filter_utils
provide a type-safe, unified and highly configurable interface for reading ROS parameters. Use the same syntax to read parameters of a node, nodelet, filter, or a custom XmlRpcValue
struct. Read an Eigen matrix, vector of unsigned ints, ros::Duration
or geometry_msgs::Vector3
directly without the need to write a single line of conversion code or value checking. Type of the value to read is automatically determined either from the provided default value, or from template parameter of the getParam<>()
function.
Example usage:
// Usage in a nodelet based on `cras::Nodelet`:
// read a parameter of size_t type defaulting to 10 if not set.
// The _sz suffix is a helper to convert a numeric literal to size_t type.
const auto params = this->privateParams();
const size_t queueSize = params->getParam("queue_size", 10_sz, "messages");
// Usage in a node:
// read array of 3 doubles from parameter server into a tf2::Vector3, defaulting to the specified vector if not set.
cras::NodeParamHelper params("~");
const tf2::Vector3 gravity = params->getParam("gravity", tf2::Vector3(0, 0, -9.81), "m.s^-2");
// Usage in a filter based on cras::FilterBase:
// read a required ros::Duration parameter from a float
// the nullopt specifies instead of the default value specifies it is required.
const ros::Duration timeout = this->getParam<ros::Duration>("timeout", cras::nullopt);
// Usage directly from a XmlRpcValue dict
// read an Eigen::Vector3d from a XmlRpcValue array
XmlRpc::XmlRpcValue values;
values["offset"][0] = 1; values["offset"][1] = 2; values["offset"][2] = 3;
auto logger = std::make_shared<cras::NodeLogHelper>();
auto paramHelper = std::make_shared<cras::XmlRpcValueGetParamAdapter>(values, "");
BoundParamHelper params(logger, paramHelper);
const Eigen::Vector3d offset = params->getParam("offset", Eigen::Vector3d::UnitX());
You can also configure the parameter lookup behavior, e.g. to throw exception if the value cannot be converted to the requested type (normally, the default value is used in such case):
// Will throw cras::GetParamException if float_param has a non-integer value
const int intParam = params->getParam("float_param", 0, "", {.throwIfConvertFails = true});
Finally, there is also a more verbose version of getParam()
that tells more about how the lookup went:
const cras::GetParamResult<int> res = params->getParamVerbose("int", 0);
const int intParam = res.value;
const bool wasDefaultUsed = res.info.defaultUsed;
diag_utils
: Easy setup of publisher/subscriber with rate and delay diagnostics
It often happens that you know some topic should be received or published at a specific rate, or with a maximum allowed delay.
Example usage:
cras::NodeHandle nh; // similarly in cras::Nodelet
diagnostic_updater::Updater updater(nh); // in cras::Nodelet, just call this->getDiagUpdater()
auto pub = nh.advertiseDiagnosed<sensor_msgs::PointCloud2>(updater, "points_topic_diag", "points_topic", 10);
This subscribes to topic /points_topic
and reads parameters /points_topic_diag
to configure the diagnostics. The parameters that are read under the /points_topic_diag
namespace are: rate/desired
, rate/min
, rate/max
, rate/tolerance
, rate/window_size
, delay/min
, delay/max
.
So e.g. with the following config:
points_topic_diag:
rate:
min: 10
max: 20
tolerance: 0.1
delay:
min: 0.1
max: 0.2
The diagnostics would be in OK status if the topic is published on rates between 9 and 22 HZ (10/20 plus 10% tolerance), and if the difference between ROS time at time of publishing and the messages stamp is between 0.1 and 0.2 seconds. Otherwise, it would report an ERROR status.
Changelog for package cras_cpp_common
2.4.2 (2024-09-05)
2.4.1 (2024-09-04)
- Fixed roslint
- Contributors: Martin Pecka
2.4.0 (2024-09-04)
- Added small_map and fixed concurrency problems in log_utils.
- Updated fast_float to 6.1.5.
- node_from_nodelet: Fixed error message
- Contributors: Martin Pecka
2.3.9 (2024-02-27)
- Removed catkin_lint buildfarm hacks.
- Updated to fast_float 6.1.0 .
- Contributors: Martin Pecka
2.3.8 (2024-01-12)
- Fixed FindFilesystem CMake module usage of try_compile
- Contributors: Martin Pecka
2.3.7 (2024-01-09)
- node_from_nodelet: Fix syntax for Melodic.
- Contributors: Martin Pecka
2.3.6 (2024-01-09)
- node_from_nodelet: Implemented a simplified version that doesn\'t need the nodelet header file.
- node_from_nodelet: Fixed a bug with missing return 0 at the end of main.
- Contributors: Martin Pecka
2.3.5 (2023-11-21)
- param_utils: Added getParam() specialization for geometry_msgs/Pose messages.
- nodelet_utils: Added Resettable interface to NodeletWithSharedTfBuffer.
- Added Resettable interface compatible with cras_py_common.
- time_utils: Added saturateAdd().
- Contributors: Martin Pecka
2.3.4 (2023-10-25)
- Do not use -march=native optimizations for cras_tf2_sensor_msgs. More generic platform-specific optimizations are used.
- Contributors: Martin Pecka
2.3.3 (2023-10-06)
2.3.2 (2023-10-06)
- Fix finding std::filesystem in CMake if a non-default launguage standard is used.
- Contributors: Martin Pecka
2.3.1 (2023-07-13)
2.3.0 (2023-07-12)
- Increased minimum CMake version to 3.10.2.
- log_utils: Fixed a potential segfault when instances of MemoryLogHelper get recycled.
- Contributors: Martin Pecka
2.2.3 (2023-06-16)
- Install node_from_nodelet targets in PACKAGE_BIN and not GLOBAL_BIN
- Contributors: Martin Pecka
2.2.2 (2023-05-15)
2.2.1 (2023-05-15)
2.2.0 (2023-04-09)
- Fixed parseFloat()/parseDouble() tests to reflect the behavior change in fast_float library.
- Update fast_float to v4.0.
- Update fast_float to v3.10.0.
- Update tl/expected.
- Update tl/optional to v1.1.0.
- string_utils: Added toLower/toUpper.
- Added std::span shim.
- Contributors: Martin Pecka
2.1.2 (2023-02-10)
2.1.1 (2023-02-08)
2.1.0 (2023-02-08)
- log_utils: Added a method to set logger to HasLogger class.
- c_api: Added outputRosMessage() method that directly serializes ROS messages into allocated buffers.
- log_utils: Added MemoryLogHelper, reworked the interface of LogHelper a bit.
- Completely reworked log_utils to use macros instead of functions. This was needed because of the static log_location variables inside ROS_ macros - e.g. _ONCE was only triggered once regardless of where was it called from. There were also not so helpful file:line data in the logged messages. Backwards compatibility was kept 99%, but there are subtle cases where it will fail - e.g. if there was [this->log->logError()]{.title-ref} right after an [if]{.title-ref} or [else]{.title-ref} without braces.
- Added c_api.h.
- Added cras::expected.
- Fixed doxygen configuration and a few documentation errors. To get a clean rosdoc_lite run, set [INPUT_FILTER = \"sed \'s/([ <])::/1/g\'\"]{.title-ref} in doxy.template in rosdoc_lite .
- xmlrpc_value_utils: Added conversion to dynamic_reconfigure/Config message.
- string_utils: Added cras::strip().
- Added std::any shim.
- Contributors: Martin Pecka
2.0.10 (2022-11-24)
2.0.9 (2022-11-24)
2.0.8 (2022-11-24)
2.0.7 (2022-11-24)
2.0.6 (2022-11-24)
2.0.5 (2022-10-23)
- Added support for std::array parameters.
- Contributors: Martin Pecka
2.0.4 (2022-10-14)
2.0.3 (2022-10-07)
- cras_py_common: Extended functionality to get closer to cras_cpp_common.
- Improved readmes and added more badges to them.
- Contributors: Martin Pecka
2.0.2 (2022-08-29)
- De-flake throttle test and enable catkin_lint when it has chance to run correctly.
- Add linters and licenses.
- Set up roslaunch-check for test files.
- added catkin_lint
- added roslint, fixed issues.
- catkin_lint, moved external folder inside include/project to avoid collisions with other projects.
- Avoid threading errors when stopping nodes created by node_from_nodelet.
- time_utils: Fix build on 32bit armhf.
- Contributors: Martin Pecka
2.0.1 (2022-08-26)
- Added LICENSE file.
- Improved node_from_nodelet to use node logger instead of nodelet logger.
- Added Github Actions CI.
- Increased test coverage, fixed bug in filter diagnostics.
- tf2_utils: Added convenience methods getRoll(), getPitch() and getYaw().
- filter_utils: Adapt to upstream changes adding FilterChain::getFilters() method.
- string_utils: Allowed to limit replace() only to the beginning or end of the string.
- string_utils: Added parseDouble() and friends.
- node_from_nodelet.cmake: Made autogenerated target names less prone to naming conflicts.
- Added more logging function variants.
- Added support for std::string format in LogHelper.
- Fix logging macros to log under correct rosconsole logger.
- Added cras_node_from_nodelet() CMake function.
- Better support for custom data types in getParam() functions.
- Rename test targets so that their names do not conflict with other projects.
- Compatibility with GCC 9+.
- Fixed invalid rate conversion.
- Backwards compatibility for StatefulNodelet::shutdown().
- Improved CMakeLists.txt and header guard placement.
- Merged cras_nodelet_topic_tools with cras_topic_tools, moved repeater and joy_repeater from cras_cpp_common to cras_topic_tools.
- Implemented rate limiters.
- Refactored nodelet_manager_sharing_tf_buffer and added tests for it.
- Added urdf_utils.h.
- Improved tf2_sensor_msgs.h and added test.
- Improved set_utils.hpp.
- Added better shim for std::optional. It now provides all relevant features.
- Added more diagnostics to filter_chain_nodelet.hpp.
- Added shim for std::bind_front into functional.hpp.
- Added running_stats.hpp implementing Welford\'s running mean and variance computation.
- Improved filter_chain_nodelet.hpp, added tests.
- Improved cloud.hpp, added tests.
- Reorganize filter_utils directory structure.
- Improved the interface of diag_utils and node_utils, added tests. Added message_utils.
- Improved the interface of nodelet_utils, added tests. Added thread_utils with tests.
- XmlRpcValue docs and code reliability.
- Better test coverage of param_utils. Improved Eigen getParam() interface.
- Improved getParam() behavior, added test_param_utils.
- First part of upgrade: log_utils, param_utils, filter_utils, node_utils, xmlrpc, cloud.
1.0.0
- Added XmlRpcValueTraits and issue an error when getParam() finds a parameter value but it has an incompatible type.
- Made FilterBase getParam() functions const. Allowed by https://github.com/ros/filters/pull/35 (released in Melodic filters 1.8.2 (October 2021) and Noetic filters 1.9.1 (September 2021)).
- Fixed diagnosed publisher creation scripts
- Little fixes, added pool allocator helpers.
- Improved diagnostics
- Fix compilation with gcc 8
- Fix for systems with old versions of diagnostic_updater
- Compatibility with diagnostic_updater 1.9.6 and newer.
- Fixed memory corruption by cras::transformOnlyChannels().
- Improve lazy subscription behavior in filter_chain_nodelet.hpp
- Fixed SEVERE_WARNING in nodelet_manager_sharing_tf_buffer.
- Fixed segfaults when unloading NodeletWithDiagnostics.
- node_utils: added paramsForNodeHandle()
- Moved filter_chain_nodelet from nifti_laser_filtering to here.
- Added missing diag functions.
- Added missing nodelet logging macros.
- Refactored param_utils to be also usable in filters.
- Small refactoring of CMakeLists.txt and related stuff, modernize header guards.
- Fixed reading of hierarchical parameters in diag_utils.hpp.
- Added diagnostics utils.
- Reworked getParam helpers, added some more utility functions.
- Added NodeletWithDiagnostics trait.
- Added utilities for working with pointclouds - generic iterator, transformOnlyChannels() and more utility functions.
- Added docs.
- Added NodeletWithSharedTfBuffer::usesSharedBuffer().
- Little fixes, verified that Eigen compiles using AVX instructions.
- Added a mixin for nodelets which share a tf buffer with their nodelet manager (and added that custom manager, too).
- Forced tf2_sensor_msgs cloud transform tools to utilize SIMD instructions.
- Improved nodelet_utils, converted all convenience functions into mixins that can be side-loaded to any class.
- Separated nodelet param loading to a separate class so that it can be utilized even in nodelets that are not descendants of cras::Nodelet().
- Added tf2_sensor_msgs with transformWithChannels() function to help correctly transforming pointclouds.
- Remove build warning.
- Fixed to_string() for collections so that it doesn\'t include the separator after the last item.
- Added getParamVerboseSet() to filter_utils.hpp
- Repeater and specific joy repeater.
- Topic repeater node (every period, instant republish option).
- Added CMake module for using the most modern C++ filesystem API available.
- Added to_string(bool) to string_utils.hpp
- filter_utils: Added support for disabling filters during runtime.
- Added to_string<std::set>()
- Added tf2_utils.
- Added ros::Time to_string.
- filter_utils: Added a possibility to specify a callback in FilterChain that is called after application of each filter.
- nodelet_utils: Added shutdown() method meant to be called from destructors.
- nodelet_utils: Added option to use nodelet-aware canTransform
- nodelet_utils: Added updateThreadName().
- Added nodelet utils.
- Added set utils.
- Added math utils.
- Added inline modifiers to avoid multiple definitions issues.
- Added std::string - const char* interop overload to getParam.
- Moved cras_cpp_common from subt/tradr-robot/tradr-resources.
- added string_utils::to_string(XmlRpc::XmlRpcValue)
- topic_utils -> string_utils, added string_utils::to_string
- Fixed bad design of filter_utils.
- added ros::Duration specializations for node_utils::getParam() and filter_utils::getParam().
- Added filter_utils, time_utils, topic_utils, added unsigned specializations for node_utils::getParam().
- Added cras_cpp_common.
- Contributors: Martin Pecka, Tomas Petricek
Wiki Tutorials
Package Dependencies
System Dependencies
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged cras_cpp_common at Robotics Stack Exchange
cras_cpp_common package from cras_ros_utils repocamera_throttle cras_bag_tools cras_cpp_common cras_docs_common cras_py_common cras_topic_tools image_transport_codecs tf_static_publisher |
|
Package Summary
Tags | No category tags. |
Version | 2.4.2 |
License | BSD |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/ctu-vras/ros-utils.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-09-05 |
Dev Status | DEVELOPED |
CI status |
|
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Martin Pecka
Authors
- Martin Pecka
cras_cpp_common
A Czech-army knife for ROS code written in C++.
The aim of this package is to provide some missing utility functions to roscpp. Using libraries from this package, you should be able to write more efficient, safer and less error-prone code without much boilerplate. As this package is intended to handle a lot of the boring code for you "behind the scenes", ubiquitous effort was put into unit-testing everything, so that you can rely on the provided code without the usual fear whether it works or not.
This readme shortly introduces the provided libraries. Detailed documentation can be found in the comments in code and in the API docs. Examples of usage can be found in the dependent packages from ros-utils
, and in the unit tests.
Parts of this package were used by team CTU-CRAS-Norlab in DARPA Subterranean Challenge.
Support and Build Status
This package is supported on Melodic and Noetic until their End of Life (and maybe later). It is occasionally tested with non-default GCC versions like Melodic+GCC8 or Noetic+GCC11.
List of provided libraries
-
any
: Provides forward compatibility forstd::any
. -
c_api
: Utilities for writing a C API for your packages. -
cloud
,tf2_sensor_msgs
: Utilities for working with pointclouds (iterators, copying, extracting channels, transforming the clouds). -
diag_utils
: Helpers for easy setup of a diagnosed publisher/subscriber that checks message rate or delay. Configuration of the expected rates/delays is via ROS parameters. -
expected
: Provides forward compatibility forstd::expected
. -
filter_utils
:-
FilterBase
eases access to filter parameters viaparam_utils
. -
FilterChain
class and nodelet improve uponfilters::FilterChain
by adding support for dynamic disabling/enabling of individual filters, diagnostics of the individual filters and possibility to publish the intermediate filtering results.
-
-
functional
: Provides forward compatibility forstd::apply()
,std::invoke()
andstd::bind_front()
. Especiallycras::bind_front()
is super useful for specifying ROS subscriber callbacks, where you just bindthis
to the callback, and the rest of the parameters is automatically handled. -
log_utils
: Unified access to theROS_*
andNODELET_*
logging macros. This is more an internal utility of this package. -
math_utils
:sgn()
signum function, andRunningStats
(computes mean and variance on a stream of data in O(1) time per sample). -
message_utils
:BaseMessage<M>
andIsMessageParam<M>
template helpers for working with ROS message classes. -
node_utils
: Integration ofdiag_utils
andparam_utils
for ROS nodes. -
nodelet_utils
:-
cras::Nodelet
base class provides integration ofdiag_utils
andparam_utils
for nodelets, adds the ability to update name of the current thread with name of the nodelet, adds support for sharing a single TF buffer between multiple nodelets, and provides anok()
method that is similar toros::ok()
, but starts returningfalse
when the nodelet is being unloaded. -
nodelet_manager_sharing_tf_buffer
is a customized nodelet manager that is able to share its own (single) TF buffer to multiple nodelets (based oncras::Nodelet
).
-
-
optional
: Provides forward compatibility forstd::optional
. -
param_utils
: Utilities for type-safe, easy, unified and configurable access to ROS parameters. See below for examples and more details. -
pool_allocator
: Provides a memory-pool-based allocator for ROS messages. It comes handy if you want to publish shared pointer messages on a high rate - it should decrease the time needed for object allocation vianew
. -
rate_limiter
: Library for intelligent rate-limiting of events (mainly messages). So far it implements the algorithm fromtopic_tools throttle
(not very good), and token bucket algorithm (pretty good for most cases). -
set_utils
: ProvidesisSetIntersectionEmpty()
working on a pair ofstd::set
s. -
small_map
: ProvidesSmallMap
andSmallSet
, variants ofstd::map
implemented usingstd::list
which are append-only and lock-free for reading. -
span
: Provides forward compatibility forstd::span
. -
string_utils
: Provides many string manipulation helpers you've always dreamed of. Universalto_string()
that converts almost anything to a sensible string.startsWith()
/endsWith()
,replace()
,contains()
,split()
/join()
,format()
(likesprintf()
but without hassle and onstd::string
),stripLeading()
/stripTrailing()
,removePrefix()
/removeSuffix()
,parseFloat()
/parseDouble()
(convert string to double independent of locale!),parseInt32()
and friends (parse many textual representations to an integer). -
suppress_warnings
: Unified macros that suppress various compiler warnings for a piece of code. -
test_utils
: Provide a hack that allows loading a locally-defined nodelet without the need to register it via package.xml. -
tf2_utils
:getRoll()
,getPitch()
,getYaw()
,getRPY()
from atf2::Quaternion
orgeometry_msgs::Quaternion
!- Also provides
InterruptibleTFBuffer
that can cooperate withcras::Nodelet
and stop a TF lookup if the nodelet is being unloaded (normally, the lookup freezes when you pause simulation time).
- Also provides
-
thread_utils
:getThreadName()
andsetThreadName()
.- Also provides
ReverseSemaphore
synchronization primitive that counts towards zero and notifies when empty.
- Also provides
-
time_utils
:remainingTime()
tells you how much of a timeout remains if you started waiting at some specified time. Conversions betweenros::Rate()
and frequency. Multiplication and division operators for ROS duration types. -
type_utils
: Provides compile-time and run-timegetTypeName()
helper that converts a C++ type to a string containing its name. -
urdf_utils
: Conversions betweenurdf
andEigen
types. -
xmlrpc_value_traits
: Type traits forXmlRpc::XmlRpcValue
. -
xmlrpc_value_utils
: Conversions betweenXmlRpc::XmlRpcValue
and C++ and STL types.
List of provided CMake helpers
-
node_from_nodelet
: Easily convert a nodelet into a standalone node executable. Seecras_topic_tools
package for an example.
param_utils
: Parameter Reading Helpers
param_utils
, node_utils
, nodelet_utils
and filter_utils
provide a type-safe, unified and highly configurable interface for reading ROS parameters. Use the same syntax to read parameters of a node, nodelet, filter, or a custom XmlRpcValue
struct. Read an Eigen matrix, vector of unsigned ints, ros::Duration
or geometry_msgs::Vector3
directly without the need to write a single line of conversion code or value checking. Type of the value to read is automatically determined either from the provided default value, or from template parameter of the getParam<>()
function.
Example usage:
// Usage in a nodelet based on `cras::Nodelet`:
// read a parameter of size_t type defaulting to 10 if not set.
// The _sz suffix is a helper to convert a numeric literal to size_t type.
const auto params = this->privateParams();
const size_t queueSize = params->getParam("queue_size", 10_sz, "messages");
// Usage in a node:
// read array of 3 doubles from parameter server into a tf2::Vector3, defaulting to the specified vector if not set.
cras::NodeParamHelper params("~");
const tf2::Vector3 gravity = params->getParam("gravity", tf2::Vector3(0, 0, -9.81), "m.s^-2");
// Usage in a filter based on cras::FilterBase:
// read a required ros::Duration parameter from a float
// the nullopt specifies instead of the default value specifies it is required.
const ros::Duration timeout = this->getParam<ros::Duration>("timeout", cras::nullopt);
// Usage directly from a XmlRpcValue dict
// read an Eigen::Vector3d from a XmlRpcValue array
XmlRpc::XmlRpcValue values;
values["offset"][0] = 1; values["offset"][1] = 2; values["offset"][2] = 3;
auto logger = std::make_shared<cras::NodeLogHelper>();
auto paramHelper = std::make_shared<cras::XmlRpcValueGetParamAdapter>(values, "");
BoundParamHelper params(logger, paramHelper);
const Eigen::Vector3d offset = params->getParam("offset", Eigen::Vector3d::UnitX());
You can also configure the parameter lookup behavior, e.g. to throw exception if the value cannot be converted to the requested type (normally, the default value is used in such case):
// Will throw cras::GetParamException if float_param has a non-integer value
const int intParam = params->getParam("float_param", 0, "", {.throwIfConvertFails = true});
Finally, there is also a more verbose version of getParam()
that tells more about how the lookup went:
const cras::GetParamResult<int> res = params->getParamVerbose("int", 0);
const int intParam = res.value;
const bool wasDefaultUsed = res.info.defaultUsed;
diag_utils
: Easy setup of publisher/subscriber with rate and delay diagnostics
It often happens that you know some topic should be received or published at a specific rate, or with a maximum allowed delay.
Example usage:
cras::NodeHandle nh; // similarly in cras::Nodelet
diagnostic_updater::Updater updater(nh); // in cras::Nodelet, just call this->getDiagUpdater()
auto pub = nh.advertiseDiagnosed<sensor_msgs::PointCloud2>(updater, "points_topic_diag", "points_topic", 10);
This subscribes to topic /points_topic
and reads parameters /points_topic_diag
to configure the diagnostics. The parameters that are read under the /points_topic_diag
namespace are: rate/desired
, rate/min
, rate/max
, rate/tolerance
, rate/window_size
, delay/min
, delay/max
.
So e.g. with the following config:
points_topic_diag:
rate:
min: 10
max: 20
tolerance: 0.1
delay:
min: 0.1
max: 0.2
The diagnostics would be in OK status if the topic is published on rates between 9 and 22 HZ (10/20 plus 10% tolerance), and if the difference between ROS time at time of publishing and the messages stamp is between 0.1 and 0.2 seconds. Otherwise, it would report an ERROR status.
Changelog for package cras_cpp_common
2.4.2 (2024-09-05)
2.4.1 (2024-09-04)
- Fixed roslint
- Contributors: Martin Pecka
2.4.0 (2024-09-04)
- Added small_map and fixed concurrency problems in log_utils.
- Updated fast_float to 6.1.5.
- node_from_nodelet: Fixed error message
- Contributors: Martin Pecka
2.3.9 (2024-02-27)
- Removed catkin_lint buildfarm hacks.
- Updated to fast_float 6.1.0 .
- Contributors: Martin Pecka
2.3.8 (2024-01-12)
- Fixed FindFilesystem CMake module usage of try_compile
- Contributors: Martin Pecka
2.3.7 (2024-01-09)
- node_from_nodelet: Fix syntax for Melodic.
- Contributors: Martin Pecka
2.3.6 (2024-01-09)
- node_from_nodelet: Implemented a simplified version that doesn\'t need the nodelet header file.
- node_from_nodelet: Fixed a bug with missing return 0 at the end of main.
- Contributors: Martin Pecka
2.3.5 (2023-11-21)
- param_utils: Added getParam() specialization for geometry_msgs/Pose messages.
- nodelet_utils: Added Resettable interface to NodeletWithSharedTfBuffer.
- Added Resettable interface compatible with cras_py_common.
- time_utils: Added saturateAdd().
- Contributors: Martin Pecka
2.3.4 (2023-10-25)
- Do not use -march=native optimizations for cras_tf2_sensor_msgs. More generic platform-specific optimizations are used.
- Contributors: Martin Pecka
2.3.3 (2023-10-06)
2.3.2 (2023-10-06)
- Fix finding std::filesystem in CMake if a non-default launguage standard is used.
- Contributors: Martin Pecka
2.3.1 (2023-07-13)
2.3.0 (2023-07-12)
- Increased minimum CMake version to 3.10.2.
- log_utils: Fixed a potential segfault when instances of MemoryLogHelper get recycled.
- Contributors: Martin Pecka
2.2.3 (2023-06-16)
- Install node_from_nodelet targets in PACKAGE_BIN and not GLOBAL_BIN
- Contributors: Martin Pecka
2.2.2 (2023-05-15)
2.2.1 (2023-05-15)
2.2.0 (2023-04-09)
- Fixed parseFloat()/parseDouble() tests to reflect the behavior change in fast_float library.
- Update fast_float to v4.0.
- Update fast_float to v3.10.0.
- Update tl/expected.
- Update tl/optional to v1.1.0.
- string_utils: Added toLower/toUpper.
- Added std::span shim.
- Contributors: Martin Pecka
2.1.2 (2023-02-10)
2.1.1 (2023-02-08)
2.1.0 (2023-02-08)
- log_utils: Added a method to set logger to HasLogger class.
- c_api: Added outputRosMessage() method that directly serializes ROS messages into allocated buffers.
- log_utils: Added MemoryLogHelper, reworked the interface of LogHelper a bit.
- Completely reworked log_utils to use macros instead of functions. This was needed because of the static log_location variables inside ROS_ macros - e.g. _ONCE was only triggered once regardless of where was it called from. There were also not so helpful file:line data in the logged messages. Backwards compatibility was kept 99%, but there are subtle cases where it will fail - e.g. if there was [this->log->logError()]{.title-ref} right after an [if]{.title-ref} or [else]{.title-ref} without braces.
- Added c_api.h.
- Added cras::expected.
- Fixed doxygen configuration and a few documentation errors. To get a clean rosdoc_lite run, set [INPUT_FILTER = \"sed \'s/([ <])::/1/g\'\"]{.title-ref} in doxy.template in rosdoc_lite .
- xmlrpc_value_utils: Added conversion to dynamic_reconfigure/Config message.
- string_utils: Added cras::strip().
- Added std::any shim.
- Contributors: Martin Pecka
2.0.10 (2022-11-24)
2.0.9 (2022-11-24)
2.0.8 (2022-11-24)
2.0.7 (2022-11-24)
2.0.6 (2022-11-24)
2.0.5 (2022-10-23)
- Added support for std::array parameters.
- Contributors: Martin Pecka
2.0.4 (2022-10-14)
2.0.3 (2022-10-07)
- cras_py_common: Extended functionality to get closer to cras_cpp_common.
- Improved readmes and added more badges to them.
- Contributors: Martin Pecka
2.0.2 (2022-08-29)
- De-flake throttle test and enable catkin_lint when it has chance to run correctly.
- Add linters and licenses.
- Set up roslaunch-check for test files.
- added catkin_lint
- added roslint, fixed issues.
- catkin_lint, moved external folder inside include/project to avoid collisions with other projects.
- Avoid threading errors when stopping nodes created by node_from_nodelet.
- time_utils: Fix build on 32bit armhf.
- Contributors: Martin Pecka
2.0.1 (2022-08-26)
- Added LICENSE file.
- Improved node_from_nodelet to use node logger instead of nodelet logger.
- Added Github Actions CI.
- Increased test coverage, fixed bug in filter diagnostics.
- tf2_utils: Added convenience methods getRoll(), getPitch() and getYaw().
- filter_utils: Adapt to upstream changes adding FilterChain::getFilters() method.
- string_utils: Allowed to limit replace() only to the beginning or end of the string.
- string_utils: Added parseDouble() and friends.
- node_from_nodelet.cmake: Made autogenerated target names less prone to naming conflicts.
- Added more logging function variants.
- Added support for std::string format in LogHelper.
- Fix logging macros to log under correct rosconsole logger.
- Added cras_node_from_nodelet() CMake function.
- Better support for custom data types in getParam() functions.
- Rename test targets so that their names do not conflict with other projects.
- Compatibility with GCC 9+.
- Fixed invalid rate conversion.
- Backwards compatibility for StatefulNodelet::shutdown().
- Improved CMakeLists.txt and header guard placement.
- Merged cras_nodelet_topic_tools with cras_topic_tools, moved repeater and joy_repeater from cras_cpp_common to cras_topic_tools.
- Implemented rate limiters.
- Refactored nodelet_manager_sharing_tf_buffer and added tests for it.
- Added urdf_utils.h.
- Improved tf2_sensor_msgs.h and added test.
- Improved set_utils.hpp.
- Added better shim for std::optional. It now provides all relevant features.
- Added more diagnostics to filter_chain_nodelet.hpp.
- Added shim for std::bind_front into functional.hpp.
- Added running_stats.hpp implementing Welford\'s running mean and variance computation.
- Improved filter_chain_nodelet.hpp, added tests.
- Improved cloud.hpp, added tests.
- Reorganize filter_utils directory structure.
- Improved the interface of diag_utils and node_utils, added tests. Added message_utils.
- Improved the interface of nodelet_utils, added tests. Added thread_utils with tests.
- XmlRpcValue docs and code reliability.
- Better test coverage of param_utils. Improved Eigen getParam() interface.
- Improved getParam() behavior, added test_param_utils.
- First part of upgrade: log_utils, param_utils, filter_utils, node_utils, xmlrpc, cloud.
1.0.0
- Added XmlRpcValueTraits and issue an error when getParam() finds a parameter value but it has an incompatible type.
- Made FilterBase getParam() functions const. Allowed by https://github.com/ros/filters/pull/35 (released in Melodic filters 1.8.2 (October 2021) and Noetic filters 1.9.1 (September 2021)).
- Fixed diagnosed publisher creation scripts
- Little fixes, added pool allocator helpers.
- Improved diagnostics
- Fix compilation with gcc 8
- Fix for systems with old versions of diagnostic_updater
- Compatibility with diagnostic_updater 1.9.6 and newer.
- Fixed memory corruption by cras::transformOnlyChannels().
- Improve lazy subscription behavior in filter_chain_nodelet.hpp
- Fixed SEVERE_WARNING in nodelet_manager_sharing_tf_buffer.
- Fixed segfaults when unloading NodeletWithDiagnostics.
- node_utils: added paramsForNodeHandle()
- Moved filter_chain_nodelet from nifti_laser_filtering to here.
- Added missing diag functions.
- Added missing nodelet logging macros.
- Refactored param_utils to be also usable in filters.
- Small refactoring of CMakeLists.txt and related stuff, modernize header guards.
- Fixed reading of hierarchical parameters in diag_utils.hpp.
- Added diagnostics utils.
- Reworked getParam helpers, added some more utility functions.
- Added NodeletWithDiagnostics trait.
- Added utilities for working with pointclouds - generic iterator, transformOnlyChannels() and more utility functions.
- Added docs.
- Added NodeletWithSharedTfBuffer::usesSharedBuffer().
- Little fixes, verified that Eigen compiles using AVX instructions.
- Added a mixin for nodelets which share a tf buffer with their nodelet manager (and added that custom manager, too).
- Forced tf2_sensor_msgs cloud transform tools to utilize SIMD instructions.
- Improved nodelet_utils, converted all convenience functions into mixins that can be side-loaded to any class.
- Separated nodelet param loading to a separate class so that it can be utilized even in nodelets that are not descendants of cras::Nodelet().
- Added tf2_sensor_msgs with transformWithChannels() function to help correctly transforming pointclouds.
- Remove build warning.
- Fixed to_string() for collections so that it doesn\'t include the separator after the last item.
- Added getParamVerboseSet() to filter_utils.hpp
- Repeater and specific joy repeater.
- Topic repeater node (every period, instant republish option).
- Added CMake module for using the most modern C++ filesystem API available.
- Added to_string(bool) to string_utils.hpp
- filter_utils: Added support for disabling filters during runtime.
- Added to_string<std::set>()
- Added tf2_utils.
- Added ros::Time to_string.
- filter_utils: Added a possibility to specify a callback in FilterChain that is called after application of each filter.
- nodelet_utils: Added shutdown() method meant to be called from destructors.
- nodelet_utils: Added option to use nodelet-aware canTransform
- nodelet_utils: Added updateThreadName().
- Added nodelet utils.
- Added set utils.
- Added math utils.
- Added inline modifiers to avoid multiple definitions issues.
- Added std::string - const char* interop overload to getParam.
- Moved cras_cpp_common from subt/tradr-robot/tradr-resources.
- added string_utils::to_string(XmlRpc::XmlRpcValue)
- topic_utils -> string_utils, added string_utils::to_string
- Fixed bad design of filter_utils.
- added ros::Duration specializations for node_utils::getParam() and filter_utils::getParam().
- Added filter_utils, time_utils, topic_utils, added unsigned specializations for node_utils::getParam().
- Added cras_cpp_common.
- Contributors: Martin Pecka, Tomas Petricek