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::Parameter | fromRosParam (const std::string &name, const XmlRpc::XmlRpcValue &value) |
foxglove::ParameterValue | fromRosParam (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::string | retrieveServiceType (const std::string &serviceName, std::chrono::milliseconds timeout_ms) |
std::vector< std::string > | splitMessageDefinitions (std::istream &stream) |
XmlRpc::XmlRpcValue | toRosParam (const foxglove::ParameterValue ¶m) |
std::string | trimString (std::string &str) |
Variables | |
constexpr char | DEFAULT_ADDRESS [] = "0.0.0.0" |
constexpr int64_t | DEFAULT_MAX_QOS_DEPTH = 25 |
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 int | DEFAULT_SERVICE_TYPE_RETRIEVAL_TIMEOUT_MS = 250 |
constexpr int | MAX_INVALID_PARAMS_TRACKED = 1000 |
constexpr double | MIN_UPDATE_PERIOD_MS = 100.0 |
constexpr char | PARAM_ADDRESS [] = "address" |
constexpr char | PARAM_ASSET_URI_ALLOWLIST [] = "asset_uri_allowlist" |
constexpr char | PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST [] = "best_effort_qos_topic_whitelist" |
constexpr char | PARAM_CAPABILITIES [] = "capabilities" |
constexpr char | PARAM_CERTFILE [] = "certfile" |
constexpr char | PARAM_CLIENT_TOPIC_WHITELIST [] = "client_topic_whitelist" |
constexpr char | PARAM_DISABLE_LOAN_MESSAGE [] = "disable_load_message" |
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 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 std::unordered_map< foxglove::ClientChannelId, Publication > foxglove_bridge::ClientPublications |
Definition at line 56 of file ros1_foxglove_bridge_nodelet.cpp.
typedef websocketpp::connection_hdl foxglove_bridge::ConnectionHandle |
Definition at line 53 of file ros1_foxglove_bridge_nodelet.cpp.
using foxglove_bridge::LogLevel = typedef foxglove::WebSocketLogLevel |
Definition at line 27 of file ros2_foxglove_bridge.hpp.
using foxglove_bridge::ParameterList = typedef std::vector<foxglove::Parameter> |
Definition at line 17 of file parameter_interface.hpp.
using foxglove_bridge::ParamUpdateFunc = typedef std::function<void(const ParameterList&)> |
Definition at line 18 of file parameter_interface.hpp.
using foxglove_bridge::Publication = typedef rclcpp::GenericPublisher::SharedPtr |
Definition at line 30 of file ros2_foxglove_bridge.hpp.
typedef std::map< ConnectionHandle, ClientPublications, std::owner_less<> > foxglove_bridge::PublicationsByClient |
Definition at line 57 of file ros1_foxglove_bridge_nodelet.cpp.
using foxglove_bridge::Subscription = typedef rclcpp::GenericSubscription::SharedPtr |
Definition at line 28 of file ros2_foxglove_bridge.hpp.
typedef std::map< ConnectionHandle, Subscription, std::owner_less<> > foxglove_bridge::SubscriptionsByClient |
Definition at line 55 of file ros1_foxglove_bridge_nodelet.cpp.
using foxglove_bridge::TopicAndDatatype = typedef std::pair<std::string, std::string> |
Definition at line 54 of file ros1_foxglove_bridge_nodelet.cpp.
std::shared_ptr<void> foxglove_bridge::allocate_message | ( | const MessageMembers * | members | ) |
Definition at line 46 of file generic_client.cpp.
void foxglove_bridge::declareParameters | ( | rclcpp::Node * | node | ) |
Definition at line 8 of file ros2_foxglove_bridge/src/param_utils.cpp.
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.
foxglove::ParameterValue foxglove_bridge::fromRosParam | ( | const XmlRpc::XmlRpcValue & | value | ) |
Definition at line 9 of file ros1_foxglove_bridge/src/param_utils.cpp.
|
inline |
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.
[in] | serviceType | The service type, e.g. "test_msgs/srv/BasicTypes" |
Definition at line 81 of file generic_client.cpp.
std::string foxglove_bridge::getTypeIntrospectionSymbolName | ( | const std::string & | serviceType | ) |
Definition at line 56 of file generic_client.cpp.
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.
std::vector< std::regex > foxglove_bridge::parseRegexStrings | ( | rclcpp::Node * | node, |
const std::vector< std::string > & | strings | ||
) |
Definition at line 184 of file ros2_foxglove_bridge/src/param_utils.cpp.
std::string foxglove_bridge::retrieveServiceType | ( | const std::string & | serviceName, |
std::chrono::milliseconds | timeout | ||
) |
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.
Looks up the service server host & port and opens a TCP connection to it to retrieve the header which contains the service type.
The implementation is similar to how ROS does it under the hood when creating a service server link: https://github.com/ros/ros_comm/blob/845f74602c7464e08ef5ac6fd9e26c97d0fe42c9/clients/roscpp/src/libros/service_manager.cpp#L246-L261 https://github.com/ros/ros_comm/blob/845f74602c7464e08ef5ac6fd9e26c97d0fe42c9/clients/roscpp/src/libros/service_server_link.cpp#L114-L130
Definition at line 24 of file service_utils.cpp.
|
inline |
XmlRpc::XmlRpcValue foxglove_bridge::toRosParam | ( | const foxglove::ParameterValue & | param | ) |
Definition at line 43 of file ros1_foxglove_bridge/src/param_utils.cpp.
|
inline |
|
constexpr |
Definition at line 44 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 34 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 45 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 33 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 43 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 32 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 50 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 51 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 48 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 12 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 28 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 19 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 24 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 15 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 25 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 27 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 26 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 16 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 18 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 17 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 22 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 11 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 13 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 21 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 20 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 23 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 14 of file ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp.
|
constexpr |
Definition at line 49 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 46 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 47 of file ros1_foxglove_bridge_nodelet.cpp.
|
constexpr |
Definition at line 41 of file generic_client.cpp.
|
constexpr |
Definition at line 42 of file generic_client.cpp.