Namespaces | |
| namespace | dynamics |
| namespace | msgs |
Classes | |
| class | CameraInfoPublisher |
| class | ConfidencePublisher |
| class | DepthPublisher |
| class | DeviceNodelet |
| class | DisparityColorPublisher |
| class | DisparityPublisher |
| class | ErrorDepthPublisher |
| class | ErrorDisparityPublisher |
| class | GenICam2RosPublisher |
| class | ImagePublisher |
| class | Points2Publisher |
| class | PoseStream |
| class | Protobuf2RosPublisher |
| class | Protobuf2RosStream |
| class | ThreadedStream |
Functions | |
| bool | getThisHostsIP (std::string &thisHostsIP, const std::string &otherHostsIP="", const std::string &networkInterface="") |
| bool | getThisHostsIP (string &thisHostsIP, const string &otherHostsIP, const string &networkInterface) |
| void | handleDynamicsStateChangeRequest (rcd::RemoteInterface::Ptr dynIF, int state, std_srvs::Trigger::Response &resp) |
| uint32_t | IPToUInt (const std::string ip) |
| bool | isIPInRange (const std::string ip, const std::string network, const std::string mask) |
| bool | isValidIPAddress (const std::string &ip) |
| sensor_msgs::ImuPtr | toRosImu (std::shared_ptr< roboception::msgs::Imu > imu) |
| geometry_msgs::PoseStampedPtr | toRosPoseStamped (std::shared_ptr< roboception::msgs::Frame > frame) |
| geometry_msgs::PoseWithCovarianceStampedPtr | toRosPoseWithCovarianceStamped (std::shared_ptr< roboception::msgs::Frame > frame) |
| tf::StampedTransform | toRosTfStampedTransform (std::shared_ptr< roboception::msgs::Frame > frame) |
| tf::Transform | toRosTfTransform (std::shared_ptr< roboception::msgs::Frame > frame) |
| bool rc::getThisHostsIP | ( | std::string & | thisHostsIP, |
| const std::string & | otherHostsIP = "", |
||
| const std::string & | networkInterface = "" |
||
| ) |
Convenience function to scan this host's (multiple) network interface(s) for a valid IP address. Users may give a hint either be specifying the preferred network interface to be used, or the IP address of another host that should be reachable from the returned IP address.
| thisHostsIP | IP address to be used as stream destination (only valid if returned true) |
| otherHostsIP | rc_visard's IP address, e.g. "192.168.0.20" |
| networkInterface | rc_visard's subnet config, e.g. "255.255.255.0" |
| bool rc::getThisHostsIP | ( | string & | thisHostsIP, |
| const string & | otherHostsIP, | ||
| const string & | networkInterface | ||
| ) |
Definition at line 76 of file net_utils.cc.
| void rc::handleDynamicsStateChangeRequest | ( | rcd::RemoteInterface::Ptr | dynIF, |
| int | state, | ||
| std_srvs::Trigger::Response & | resp | ||
| ) |
Definition at line 987 of file device_nodelet.cc.
| uint32_t rc::IPToUInt | ( | const std::string | ip | ) |
Converts a string-represented ip into uint (e.g. for subnet masking) taken from: https://www.stev.org/post/ccheckanipaddressisinaipmask
| ip |
Definition at line 47 of file net_utils.cc.
| bool rc::isIPInRange | ( | const std::string | ip, |
| const std::string | network, | ||
| const std::string | mask | ||
| ) |
Checks if a given ip is in range of a network defined by ip/subnet taken from: https://www.stev.org/post/ccheckanipaddressisinaipmask
| ip | |
| network | |
| mask |
Definition at line 61 of file net_utils.cc.
| bool rc::isValidIPAddress | ( | const std::string & | ip | ) |
Checks if given string is a valid IP address
| ip | IP address to be checked |
Definition at line 138 of file net_utils.cc.
| sensor_msgs::ImuPtr rc::toRosImu | ( | std::shared_ptr< roboception::msgs::Imu > | imu | ) |
Definition at line 18 of file protobuf2ros_conversions.cc.
| geometry_msgs::PoseStampedPtr rc::toRosPoseStamped | ( | std::shared_ptr< roboception::msgs::Frame > | frame | ) |
Definition at line 35 of file protobuf2ros_conversions.cc.
| geometry_msgs::PoseWithCovarianceStampedPtr rc::toRosPoseWithCovarianceStamped | ( | std::shared_ptr< roboception::msgs::Frame > | frame | ) |
Definition at line 54 of file protobuf2ros_conversions.cc.
| tf::StampedTransform rc::toRosTfStampedTransform | ( | std::shared_ptr< roboception::msgs::Frame > | frame | ) |
Definition at line 93 of file protobuf2ros_conversions.cc.
| tf::Transform rc::toRosTfTransform | ( | std::shared_ptr< roboception::msgs::Frame > | frame | ) |
Definition at line 78 of file protobuf2ros_conversions.cc.