Class GenericSensorNode

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class GenericSensorNode : public rclcpp::Node

Public Functions

explicit GenericSensorNode(const std::string &nodeName = "generic_sensor_node")
~GenericSensorNode()
void init()

Initialize from INI file and section given by ROS2 parameters:

void init(const char *templateText, const std::vector<TemplateParameter> &rosParams, const std::vector<std::string> &sections = {"SENSOR"})

Initialize from the given template text with a set of ROS2 parameters:

void init(const mrpt::config::CConfigFileBase &config, const std::vector<std::string> &sections = {"SENSOR"})

Initialize from the given configuration source:

void run()
template<class MSG_T, class PUB_T>
inline void ensure_publisher_exists(PUB_T &pub, const std::string &topicSuffix = "")
std_msgs::msg::Header create_header(const mrpt::obs::CObservation &o)
inline const auto sensor_frame_id() const
inline const auto publish_topic() const

Public Members

std::function<void(const mrpt::obs::CObservation::Ptr&)> custom_process_sensor

Once the observation is published as MRPT CObservation (if enabled), it will be published as a ROS message by process_observation(), unless a derived class implements this to handle it in a particular way.

std::function<void()> init_sensor_specific
rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr imu_publisher_
rclcpp::Publisher<sensor_msgs::msg::NavSatFix>::SharedPtr gps_publisher_
std::map<std::string, rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr> images_publisher_
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_bc_
struct TemplateParameter

Public Members

std::string ros_param_name
std::string template_variable
std::string default_value
bool required