7#ifndef YARP_ROS2_BATTERY_NWS_ROS2_H
8#define YARP_ROS2_BATTERY_NWS_ROS2_H
9#include <rclcpp/rclcpp.hpp>
10#include <sensor_msgs/msg/battery_state.hpp>
19#define DEFAULT_THREAD_PERIOD 0.02
45 bool close()
override;
62 sensor_msgs::msg::BatteryState battMsg;
63 rclcpp::Node::SharedPtr m_node;
64 rclcpp::Publisher<sensor_msgs::msg::BatteryState>::SharedPtr m_ros2Publisher =
nullptr;
This class is the parameters parser for class Battery_nws_ros2.
Battery_nws_ros2: A ros2 nws to get the status of a battery and publish it on a ros2 topic....
bool close() override
Close the DeviceDriver.
void run() override
Loop function.
bool detach() override
Detach the object (you must have first called attach).
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
void threadRelease() override
Release method.
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
bool threadInit() override
Initialization method.
Interface implemented by all device drivers.
A generic battery interface.
A container for a device driver.
Helper interface for an object that can wrap/or "attach" to a single other device.
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
An abstraction for a time stamp and/or sequence number.