Classes | Typedefs | Functions | Variables
foxglove_bridge Namespace Reference

Classes

class  FoxgloveBridge
 
class  GenericClient
 
struct  GenericService
 
class  ParameterInterface
 

Typedefs

using ClientPublications = std::unordered_map< foxglove::ClientChannelId, ros::Publisher >
 
using ConnectionHandle = websocketpp::connection_hdl
 
using LogLevel = foxglove::WebSocketLogLevel
 
using ParameterList = std::vector< foxglove::Parameter >
 
using ParamUpdateFunc = std::function< void(const ParameterList &)>
 
using Publication = rclcpp::GenericPublisher::SharedPtr
 
using PublicationsByClient = std::map< ConnectionHandle, ClientPublications, std::owner_less<> >
 
using Subscription = rclcpp::GenericSubscription::SharedPtr
 
using SubscriptionsByClient = std::map< ConnectionHandle, ros::Subscriber, std::owner_less<> >
 
using TopicAndDatatype = std::pair< std::string, std::string >
 

Functions

std::shared_ptr< void > allocate_message (const MessageMembers *members)
 
void declareParameters (rclcpp::Node *node)
 
foxglove::ParameterValue fromRosParam (const XmlRpc::XmlRpcValue &value)
 
foxglove::Parameter fromRosParam (const std::string &name, const XmlRpc::XmlRpcValue &value)
 
std::pair< std::string, std::string > getNodeAndNodeNamespace (const std::string &fqnNodeName)
 
std::string getServiceTypeSupportHandleSymbolName (const std::string &serviceType)
 
std::string getTypeIntrospectionSymbolName (const std::string &serviceType)
 
std::vector< std::regex > parseRegexPatterns (const std::vector< std::string > &strings)
 
std::vector< std::regex > parseRegexStrings (rclcpp::Node *node, const std::vector< std::string > &strings)
 
std::future< std::string > retrieveServiceType (const std::string &serviceName)
 
XmlRpc::XmlRpcValue toRosParam (const foxglove::ParameterValue &param)
 

Variables

constexpr char DEFAULT_ADDRESS [] = "0.0.0.0"
 
constexpr int64_t DEFAULT_MAX_QOS_DEPTH = 10
 
constexpr int DEFAULT_MAX_UPDATE_MS = 5000
 
constexpr int64_t DEFAULT_MIN_QOS_DEPTH = 1
 
constexpr int DEFAULT_PORT = 8765
 
constexpr int64_t DEFAULT_SEND_BUFFER_LIMIT = 10000000
 
constexpr double MIN_UPDATE_PERIOD_MS = 100.0
 
constexpr char PARAM_ADDRESS [] = "address"
 
constexpr char PARAM_CAPABILITIES [] = "capabilities"
 
constexpr char PARAM_CERTFILE [] = "certfile"
 
constexpr char PARAM_CLIENT_TOPIC_WHITELIST [] = "client_topic_whitelist"
 
constexpr char PARAM_INCLUDE_HIDDEN [] = "include_hidden"
 
constexpr char PARAM_KEYFILE [] = "keyfile"
 
constexpr char PARAM_MAX_QOS_DEPTH [] = "max_qos_depth"
 
constexpr char PARAM_MIN_QOS_DEPTH [] = "min_qos_depth"
 
constexpr char PARAM_PARAMETER_WHITELIST [] = "param_whitelist"
 
constexpr char PARAM_PORT [] = "port"
 
constexpr char PARAM_SEND_BUFFER_LIMIT [] = "send_buffer_limit"
 
constexpr char PARAM_SERVICE_WHITELIST [] = "service_whitelist"
 
constexpr char PARAM_TOPIC_WHITELIST [] = "topic_whitelist"
 
constexpr char PARAM_USE_COMPRESSION [] = "use_compression"
 
constexpr char PARAM_USETLS [] = "tls"
 
constexpr uint32_t PUBLICATION_QUEUE_LENGTH = 10
 
constexpr char ROS1_CHANNEL_ENCODING [] = "ros1"
 
constexpr int SERVICE_TYPE_RETRIEVAL_TIMEOUT_MS = 250
 
constexpr uint32_t SUBSCRIPTION_QUEUE_LENGTH = 10
 
constexpr char TYPESUPPORT_INTROSPECTION_LIB_NAME [] = "rosidl_typesupport_introspection_cpp"
 
constexpr char TYPESUPPORT_LIB_NAME [] = "rosidl_typesupport_cpp"
 

Typedef Documentation

◆ ClientPublications

Definition at line 54 of file ros1_foxglove_bridge_nodelet.cpp.

◆ ConnectionHandle

typedef websocketpp::connection_hdl foxglove_bridge::ConnectionHandle

Definition at line 51 of file ros1_foxglove_bridge_nodelet.cpp.

◆ LogLevel

Definition at line 25 of file ros2_foxglove_bridge.hpp.

◆ ParameterList

Definition at line 17 of file parameter_interface.hpp.

◆ ParamUpdateFunc

using foxglove_bridge::ParamUpdateFunc = typedef std::function<void(const ParameterList&)>

Definition at line 18 of file parameter_interface.hpp.

◆ Publication

using foxglove_bridge::Publication = typedef rclcpp::GenericPublisher::SharedPtr

Definition at line 28 of file ros2_foxglove_bridge.hpp.

◆ PublicationsByClient

Definition at line 55 of file ros1_foxglove_bridge_nodelet.cpp.

◆ Subscription

using foxglove_bridge::Subscription = typedef rclcpp::GenericSubscription::SharedPtr

Definition at line 26 of file ros2_foxglove_bridge.hpp.

◆ SubscriptionsByClient

typedef std::map< ConnectionHandle, Subscription, std::owner_less<> > foxglove_bridge::SubscriptionsByClient

Definition at line 53 of file ros1_foxglove_bridge_nodelet.cpp.

◆ TopicAndDatatype

using foxglove_bridge::TopicAndDatatype = typedef std::pair<std::string, std::string>

Definition at line 52 of file ros1_foxglove_bridge_nodelet.cpp.

Function Documentation

◆ allocate_message()

std::shared_ptr<void> foxglove_bridge::allocate_message ( const MessageMembers *  members)

Definition at line 45 of file generic_client.cpp.

◆ declareParameters()

void foxglove_bridge::declareParameters ( rclcpp::Node *  node)

Definition at line 8 of file ros2_foxglove_bridge/src/param_utils.cpp.

◆ fromRosParam() [1/2]

foxglove::ParameterValue foxglove_bridge::fromRosParam ( const XmlRpc::XmlRpcValue value)

Definition at line 9 of file ros1_foxglove_bridge/src/param_utils.cpp.

◆ fromRosParam() [2/2]

foxglove::Parameter foxglove_bridge::fromRosParam ( const std::string &  name,
const XmlRpc::XmlRpcValue value 
)

Definition at line 39 of file ros1_foxglove_bridge/src/param_utils.cpp.

◆ getNodeAndNodeNamespace()

std::pair<std::string, std::string> foxglove_bridge::getNodeAndNodeNamespace ( const std::string &  fqnNodeName)
inline

Definition at line 12 of file utils.hpp.

◆ getServiceTypeSupportHandleSymbolName()

std::string foxglove_bridge::getServiceTypeSupportHandleSymbolName ( const std::string &  serviceType)

The default symbol names for getting type support handles for services are missing from the rosidl_typesupport_cpp shared libraries, see https://github.com/ros2/rosidl_typesupport/issues/122

We can however, as a (hacky) workaround, use other symbols defined in the shared library. With nm -C -D /opt/ros/humble/lib/libtest_msgs__rosidl_typesupport_cpp.so we see that there is rosidl_service_type_support_t const* rosidl_typesupport_cpp::get_service_type_support_handle<test_msgs::srv::BasicTypes>() which mangled becomes _ZN22rosidl_typesupport_cpp31get_service_type_support_handleIN9test_msgs3srv10BasicTypesEEEPK29rosidl_service_type_support_tv This is the same for galactic, humble and rolling (tested with gcc / clang)

This function produces the mangled symbol name for a given service type.

Parameters
[in]serviceTypeThe service type, e.g. "test_msgs/srv/BasicTypes"
Returns
Symbol name for getting the service type support handle

Definition at line 80 of file generic_client.cpp.

◆ getTypeIntrospectionSymbolName()

std::string foxglove_bridge::getTypeIntrospectionSymbolName ( const std::string &  serviceType)

Definition at line 55 of file generic_client.cpp.

◆ parseRegexPatterns()

std::vector< std::regex > foxglove_bridge::parseRegexPatterns ( const std::vector< std::string > &  strings)

Definition at line 75 of file ros1_foxglove_bridge/src/param_utils.cpp.

◆ parseRegexStrings()

std::vector< std::regex > foxglove_bridge::parseRegexStrings ( rclcpp::Node *  node,
const std::vector< std::string > &  strings 
)

Definition at line 151 of file ros2_foxglove_bridge/src/param_utils.cpp.

◆ retrieveServiceType()

std::future< std::string > foxglove_bridge::retrieveServiceType ( const std::string &  serviceName)

Opens a socket to the service server and retrieves the service type from the connection header. This is necessary as the service type is not stored on the ROS master.

Definition at line 9 of file service_utils.cpp.

◆ toRosParam()

XmlRpc::XmlRpcValue foxglove_bridge::toRosParam ( const foxglove::ParameterValue param)

Definition at line 43 of file ros1_foxglove_bridge/src/param_utils.cpp.

Variable Documentation

◆ DEFAULT_ADDRESS

constexpr char foxglove_bridge::DEFAULT_ADDRESS = "0.0.0.0"

Definition at line 43 of file ros1_foxglove_bridge_nodelet.cpp.

◆ DEFAULT_MAX_QOS_DEPTH

constexpr int64_t foxglove_bridge::DEFAULT_MAX_QOS_DEPTH = 10

◆ DEFAULT_MAX_UPDATE_MS

constexpr int foxglove_bridge::DEFAULT_MAX_UPDATE_MS = 5000

Definition at line 44 of file ros1_foxglove_bridge_nodelet.cpp.

◆ DEFAULT_MIN_QOS_DEPTH

constexpr int64_t foxglove_bridge::DEFAULT_MIN_QOS_DEPTH = 1

◆ DEFAULT_PORT

constexpr int64_t foxglove_bridge::DEFAULT_PORT = 8765

Definition at line 42 of file ros1_foxglove_bridge_nodelet.cpp.

◆ DEFAULT_SEND_BUFFER_LIMIT

constexpr int64_t foxglove_bridge::DEFAULT_SEND_BUFFER_LIMIT = 10000000

◆ MIN_UPDATE_PERIOD_MS

constexpr double foxglove_bridge::MIN_UPDATE_PERIOD_MS = 100.0

Definition at line 47 of file ros1_foxglove_bridge_nodelet.cpp.

◆ PARAM_ADDRESS

constexpr char foxglove_bridge::PARAM_ADDRESS[] = "address"

◆ PARAM_CAPABILITIES

constexpr char foxglove_bridge::PARAM_CAPABILITIES[] = "capabilities"

◆ PARAM_CERTFILE

constexpr char foxglove_bridge::PARAM_CERTFILE[] = "certfile"

◆ PARAM_CLIENT_TOPIC_WHITELIST

constexpr char foxglove_bridge::PARAM_CLIENT_TOPIC_WHITELIST[] = "client_topic_whitelist"

◆ PARAM_INCLUDE_HIDDEN

constexpr char foxglove_bridge::PARAM_INCLUDE_HIDDEN[] = "include_hidden"

◆ PARAM_KEYFILE

constexpr char foxglove_bridge::PARAM_KEYFILE[] = "keyfile"

◆ PARAM_MAX_QOS_DEPTH

constexpr char foxglove_bridge::PARAM_MAX_QOS_DEPTH[] = "max_qos_depth"

◆ PARAM_MIN_QOS_DEPTH

constexpr char foxglove_bridge::PARAM_MIN_QOS_DEPTH[] = "min_qos_depth"

◆ PARAM_PARAMETER_WHITELIST

constexpr char foxglove_bridge::PARAM_PARAMETER_WHITELIST[] = "param_whitelist"

◆ PARAM_PORT

constexpr char foxglove_bridge::PARAM_PORT[] = "port"

◆ PARAM_SEND_BUFFER_LIMIT

constexpr char foxglove_bridge::PARAM_SEND_BUFFER_LIMIT[] = "send_buffer_limit"

◆ PARAM_SERVICE_WHITELIST

constexpr char foxglove_bridge::PARAM_SERVICE_WHITELIST[] = "service_whitelist"

◆ PARAM_TOPIC_WHITELIST

constexpr char foxglove_bridge::PARAM_TOPIC_WHITELIST[] = "topic_whitelist"

◆ PARAM_USE_COMPRESSION

constexpr char foxglove_bridge::PARAM_USE_COMPRESSION[] = "use_compression"

◆ PARAM_USETLS

constexpr char foxglove_bridge::PARAM_USETLS[] = "tls"

◆ PUBLICATION_QUEUE_LENGTH

constexpr uint32_t foxglove_bridge::PUBLICATION_QUEUE_LENGTH = 10

Definition at line 48 of file ros1_foxglove_bridge_nodelet.cpp.

◆ ROS1_CHANNEL_ENCODING

constexpr char foxglove_bridge::ROS1_CHANNEL_ENCODING[] = "ros1"

Definition at line 45 of file ros1_foxglove_bridge_nodelet.cpp.

◆ SERVICE_TYPE_RETRIEVAL_TIMEOUT_MS

constexpr int foxglove_bridge::SERVICE_TYPE_RETRIEVAL_TIMEOUT_MS = 250

Definition at line 49 of file ros1_foxglove_bridge_nodelet.cpp.

◆ SUBSCRIPTION_QUEUE_LENGTH

constexpr uint32_t foxglove_bridge::SUBSCRIPTION_QUEUE_LENGTH = 10

Definition at line 46 of file ros1_foxglove_bridge_nodelet.cpp.

◆ TYPESUPPORT_INTROSPECTION_LIB_NAME

constexpr char foxglove_bridge::TYPESUPPORT_INTROSPECTION_LIB_NAME[] = "rosidl_typesupport_introspection_cpp"

Definition at line 40 of file generic_client.cpp.

◆ TYPESUPPORT_LIB_NAME

constexpr char foxglove_bridge::TYPESUPPORT_LIB_NAME[] = "rosidl_typesupport_cpp"

Definition at line 41 of file generic_client.cpp.



foxglove_bridge
Author(s): Foxglove
autogenerated on Mon Jul 3 2023 02:12:22