YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Battery_nws_ros2.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6
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>
11
12#include <yarp/dev/IBattery.h>
14#include <yarp/os/Stamp.h>
18
19#define DEFAULT_THREAD_PERIOD 0.02 //s
20
38{
39public:
42
43 // DeviceDriver
44 bool open(yarp::os::Searchable &params) override;
45 bool close() override;
46
47 // WrapperSingle
48 bool attach(yarp::dev::PolyDriver* driver) override;
49 bool detach() override;
50
51 // PeriodicThread
52 bool threadInit() override;
53 void threadRelease() override;
54 void run() override;
55
56
57private:
58 // stamp count for timestamp
59 yarp::os::Stamp m_timeStamp;
60
61 //ros2 node
62 sensor_msgs::msg::BatteryState battMsg;
63 rclcpp::Node::SharedPtr m_node;
64 rclcpp::Publisher<sensor_msgs::msg::BatteryState>::SharedPtr m_ros2Publisher =nullptr;
65
66 //interfaces
67 yarp::dev::PolyDriver m_driver;
68 yarp::dev::IBattery *m_battery_interface{nullptr};
69};
70
71#endif // YARP_ROS2_BATTERY_NWS_ROS2_H
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 &params) override
Open the DeviceDriver.
bool threadInit() override
Initialization method.
Interface implemented by all device drivers.
A generic battery interface.
Definition IBattery.h:26
A container for a device driver.
Definition PolyDriver.h:23
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.
Definition Searchable.h:31
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21