Skip to content

Commit

Permalink
Update
Browse files Browse the repository at this point in the history
  • Loading branch information
john-maidbot committed Aug 12, 2023
1 parent 7026142 commit 2443c04
Show file tree
Hide file tree
Showing 14 changed files with 387 additions and 374 deletions.
15 changes: 6 additions & 9 deletions include/point_cloud_transport/expected.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,18 +58,15 @@ using ::tl::unexpected;

namespace cras
{
/**
* \brief Type trait determining whether type T is cras::expected or not.
* \tparam T The type to test.
*/
/// \brief Type trait determining whether type T is cras::expected or not.
/// \tparam T The type to test.
template<typename T>
struct is_cras_expected : public ::std::false_type {};

/**
* \brief Type trait determining whether type T is std::optional or not.
* \tparam T Type of the expected value.
* \tparam E Type of the expected error.
*/

/// \brief Type trait determining whether type T is std::optional or not.
/// \tparam T Type of the expected value.
/// \tparam E Type of the expected error.
template<typename T, typename E>
struct is_cras_expected<::cras::expected<T, E>>: public ::std::true_type {};
} // namespace cras
Expand Down
158 changes: 75 additions & 83 deletions include/point_cloud_transport/point_cloud_codec.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,7 @@
namespace point_cloud_transport
{

/**
* Class to expose all the functionality of pointcloud transport (encode/decode msgs) without needing to spin a node.
*/
//! Class to expose all the functionality of pointcloud transport (encode/decode msgs) without needing to spin a node.

class PointCloudCodec
{
Expand All @@ -61,126 +59,120 @@ class PointCloudCodec
//! Destructor
virtual ~PointCloudCodec();

/**
* Get a shared pointer to an instance of a publisher plugin given its transport name (publishers encode messages).
* e.g. if you want the raw encoder, call getEncoderByName("raw").
*
* \param name The name of the transport to load.
* \returns A shared pointer to the publisher plugin.
*/
/// \brief Get a shared pointer to an instance of a publisher plugin given its transport name (publishers encode messages).
/// e.g. if you want the raw encoder, call getEncoderByName("raw").
///
/// \param name The name of the transport to load.
/// \returns A shared pointer to the publisher plugin.
std::shared_ptr<point_cloud_transport::PublisherPlugin> getEncoderByName(
const std::string & name);

/**
* Get a shared pointer to an instance of a publisher plugin given its transport name (subscribers decode messages).
* e.g. if you want the raw decoder, call getDecoderByName("raw").
*
* \param name The name of the transport to load.
* \returns A shared pointer to the subscriber plugin.
*/
/// \brief Get a shared pointer to an instance of a publisher plugin given its transport name (subscribers decode messages).
/// e.g. if you want the raw decoder, call getDecoderByName("raw").
///
/// \param name The name of the transport to load.
/// \returns A shared pointer to the subscriber plugin.
std::shared_ptr<point_cloud_transport::SubscriberPlugin> getDecoderByName(
const std::string & name);

/**
* Get a list of all the transports that can be loaded.
*
* \param[out] transports Vector of the loadable transport plugins.
* \param[out] names Vector of string identifieries for the transport provided by each plugin
*/
///
/// \brief Get a list of all the transports that can be loaded.
///
/// \param[out] transports Vector of the loadable transport plugins.
/// \param[out] names Vector of string identifieries for the transport provided by each plugin
///
void getLoadableTransports(
std::vector<std::string> & transports,
std::vector<std::string> & names);

/**
* Get a list of all the transport plugins, topics, transport names, and their data types that can be loaded.
*
* \param[in] baseTopic The base topic to use for the transport.
* \param[out] transports Vector of the loadable transport plugins.
* \param[out] topics Vector of the topics that can be published.
* \param[out] names Vector of string identifieries for the transport provided by each plugin
* \param[out] dataTypes Vector of the data types the transports encode a PointCloud2 into
*/
///
/// \brief Get a list of all the transport plugins, topics, transport names, and their data types that can be loaded.
///
/// \param[in] baseTopic The base topic to use for the transport.
/// \param[out] transports Vector of the loadable transport plugins.
/// \param[out] topics Vector of the topics that can be published.
/// \param[out] names Vector of string identifieries for the transport provided by each plugin
/// \param[out] dataTypes Vector of the data types the transports encode a PointCloud2 into
///
void getTopicsToPublish(
const std::string & baseTopic,
std::vector<std::string> & transports,
std::vector<std::string> & topics,
std::vector<std::string> & names,
std::vector<std::string> & dataTypes);

/**
* Get the topic, transport name, and data type that a given topic is published on for a particular transport plugin.
*
* \param[in] baseTopic The base topic to use for the transport.
* \param[in] transport The transport plugin to load.
* \param[out] topic The topic that should be subscribed to.
* \param[out] name String identifier for the transport provided by the plugin
* \param[out] dataType The data type the transport encodes a PointCloud2 into
*/
///
/// \brief Get the topic, transport name, and data type that a given topic is published on for a particular transport plugin.
///
/// \param[in] baseTopic The base topic to use for the transport.
/// \param[in] transport The transport plugin to load.
/// \param[out] topic The topic that should be subscribed to.
/// \param[out] name String identifier for the transport provided by the plugin
/// \param[out] dataType The data type the transport encodes a PointCloud2 into
///
void getTopicToSubscribe(
const std::string & baseTopic,
const std::string & transport,
std::string & topic,
std::string & name,
std::string & dataType);

/**
* Encode a PointCloud2 message into a serialized message
* using the specified transport plugin. The underlying type
* of the serialized message is determined by the transport plugin,
* but doesnt need to be known by this function.
*
* \param[in] transport_name The name of the transport plugin to use.
* \param[in] msg The message to encode.
* \param[out] serialized_msg The serialized message to store the encoded message in.
* \returns True if the message was successfully encoded, false otherwise.
*/
///
/// \brief Encode a PointCloud2 message into a serialized message
/// using the specified transport plugin. The underlying type
/// of the serialized message is determined by the transport plugin,
/// but doesnt need to be known by this function.
///
/// \param[in] transport_name The name of the transport plugin to use.
/// \param[in] msg The message to encode.
/// \param[out] serialized_msg The serialized message to store the encoded message in.
/// \returns True if the message was successfully encoded, false otherwise.
///
bool encode(
const std::string & transport_name,
const sensor_msgs::msg::PointCloud2 & msg,
rclcpp::SerializedMessage & serialized_msg);

/**
* Encode a PointCloud2 message into some compressed message type
* using the specified transport plugin. The compressed message type
* is determined by the transport plugin.
*
* \param[in] transport_name The name of the transport plugin to use.
* \param[in] msg The message to encode.
* \param[out] compressed_msg The compressed message to store the encoded message in.
* \returns True if the message was successfully encoded, false otherwise.
*/
///
/// \brief Encode a PointCloud2 message into some compressed message type
/// using the specified transport plugin. The compressed message type
/// is determined by the transport plugin.
///
/// \param[in] transport_name The name of the transport plugin to use.
/// \param[in] msg The message to encode.
/// \param[out] compressed_msg The compressed message to store the encoded message in.
/// \returns True if the message was successfully encoded, false otherwise.
///
template<class M>
bool encodeTyped(
const std::string & transport_name,
const sensor_msgs::msg::PointCloud2 & msg,
M & compressed_msg);

/**
* Dencode a serialized message into a PointCloud2
* using the specified transport plugin. The underlying type
* of the serialized message is determined by the transport plugin,
* but doesnt need to be known by this function.
*
* \param[in] transport_name The name of the transport plugin to use.
* \param[in] serialized_msg The serialized message to decode.
* \param[out] msg The message to store the decoded output in.
* \returns True if the message was successfully decoded, false otherwise.
*/
/// \brief Decode a serialized message into a PointCloud2
/// using the specified transport plugin. The underlying type
/// of the serialized message is determined by the transport plugin,
/// but doesnt need to be known by this function.
///
/// \param[in] transport_name The name of the transport plugin to use.
/// \param[in] serialized_msg The serialized message to decode.
/// \param[out] msg The message to store the decoded output in.
/// \returns True if the message was successfully decoded, false otherwise.
///
bool decode(
const std::string & transport_name,
const rclcpp::SerializedMessage & serialized_msg,
sensor_msgs::msg::PointCloud2 & msg);

/**
* Decode some compressed message type
* into a PointCloud2 based on the specified transport plugin. The compressed message type
* is determined by the transport plugin.
*
* \param[in] transport_name The name of the transport plugin to use.
* \param[in] compressed_msg The compressed message to decode.
* \param[out] msg The message to store the decoded output in.
* \returns True if the message was successfully decoded, false otherwise.
*/
/// \brief Decode some compressed message type
/// into a PointCloud2 based on the specified transport plugin. The compressed message type
/// is determined by the transport plugin.
///
/// \param[in] transport_name The name of the transport plugin to use.
/// \param[in] compressed_msg The compressed message to decode.
/// \param[out] msg The message to store the decoded output in.
/// \returns True if the message was successfully decoded, false otherwise.
///
template<class M>
bool decodeTyped(
const std::string & transport_name,
Expand Down
28 changes: 23 additions & 5 deletions include/point_cloud_transport/point_cloud_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,27 +39,45 @@
namespace point_cloud_transport
{

/**
* \brief Replacement for uses of boost::erase_last_copy
*/
/// @brief Remove the last copy of the given substring from the given string.
/// @param input original string
/// @param search substring to remove the last entry of
/// @return "input" with the last entry of "search" removed
POINT_CLOUD_TRANSPORT_PUBLIC
std::string erase_last_copy(const std::string & input, const std::string & search);

/// @brief Split a string into substrings using the given delimiter.
/// @param str string to split
/// @param delimiter delimiter to split on
/// @param maxSplits limit on the max number of splits to perform (-1 for unlimited splits)
/// @return vector of string tokens
POINT_CLOUD_TRANSPORT_PUBLIC
std::vector<std::string> split(
const std::string & str, const std::string & delimiter,
int maxSplits = -1);

// from cras::string_utils
/// @brief Check if a string ends with a given suffix. (from cras::string_utils)
/// @param str string to check
/// @param suffix suffix to check for
/// @return true if "str" ends with "suffix", false otherwise
POINT_CLOUD_TRANSPORT_PUBLIC
bool endsWith(const std::string & str, const std::string & suffix);

// from cras::string_utils
/// @brief Remove a suffix from a string if it exists.
/// @param str string to remove suffix from
/// @param suffix suffix to remove
/// @param hadSuffix if non-null, set to true if "str" had "suffix" at the end
/// @return "str" with "suffix" removed
POINT_CLOUD_TRANSPORT_PUBLIC
std::string removeSuffix(
const std::string & str, const std::string & suffix,
bool * hadSuffix = nullptr);

/// @brief Check if the given transport matches the given name.
/// @param lookup_name name of the transport to check
/// @param name name to check against
/// @param suffix suffix to remove from name before checking for equality
/// @return true if "lookup_name" matches "name" with "suffix" removed, false otherwise
POINT_CLOUD_TRANSPORT_PUBLIC
bool transportNameMatches(
const std::string & lookup_name,
Expand Down
Loading

0 comments on commit 2443c04

Please sign in to comment.