Skip to content

Commit

Permalink
Added ParamsParser to Battery_nws_ros2
Browse files Browse the repository at this point in the history
Signed-off-by: Ettore Landini <[email protected]>
  • Loading branch information
elandini84 committed Aug 26, 2024
1 parent 3a1f4de commit 8a5280e
Show file tree
Hide file tree
Showing 6 changed files with 228 additions and 43 deletions.
33 changes: 4 additions & 29 deletions src/devices/battery_nws_ros2/Battery_nws_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,42 +57,17 @@ bool Battery_nws_ros2::threadInit()

bool Battery_nws_ros2::open(yarp::os::Searchable &config)
{
if (!config.check("period")) {
yCWarning(BATTERY_NWS_ROS2) << "missing 'period' parameter, using default value of" << DEFAULT_THREAD_PERIOD;
} else {
m_period = config.find("period").asFloat64();
}

if (!config.check("node_name")) {
yCError(BATTERY_NWS_ROS2) << "missing node_name parameter";
return false;
}
m_nodeName = config.find("node_name").asString();
if (m_nodeName[0] == '/') {
yCError(BATTERY_NWS_ROS2) << "node_name parameter cannot begin with '/'";
return false;
}

if (!config.check("topic_name")) {
yCError(BATTERY_NWS_ROS2) << "missing topic_name parameter";
return false;
}
m_topicName = config.find("topic_name").asString();
if (m_topicName[0] != '/') {
yCError(BATTERY_NWS_ROS2) << "missing initial / in topic_name parameter";
return false;
}

parseParams(config);
rclcpp::NodeOptions node_options;
node_options.allow_undeclared_parameters(true);
node_options.automatically_declare_parameters_from_overrides(true);
m_node = NodeCreator::createNode(m_nodeName, node_options);
m_node = NodeCreator::createNode(m_node_name, node_options);
if (m_node == nullptr) {
yCError(BATTERY_NWS_ROS2) << " opening " << m_nodeName << " Node, check your yarp-ROS2 network configuration\n";
yCError(BATTERY_NWS_ROS2) << " opening " << m_node_name << " Node, check your yarp-ROS2 network configuration\n";
return false;
}

m_ros2Publisher = m_node->create_publisher<sensor_msgs::msg::BatteryState>(m_topicName, 10);
m_ros2Publisher = m_node->create_publisher<sensor_msgs::msg::BatteryState>(m_topic_name, 10);
return true;
}

Expand Down
18 changes: 4 additions & 14 deletions src/devices/battery_nws_ros2/Battery_nws_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <yarp/os/Stamp.h>
#include <yarp/dev/DeviceDriver.h>
#include <yarp/dev/WrapperSingle.h>
#include "Battery_nws_ros2_ParamsParser.h"

#define DEFAULT_THREAD_PERIOD 0.02 //s

Expand All @@ -24,20 +25,16 @@
* \brief `Battery_nws_ros2`: A ros2 nws to get the status of a battery and publish it on a ros2 topic.
* The attached device must implement a `yarp::dev::IBattery` interface.
*
* Parameters required by this device are:
* | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes |
* |:-------------------:|:-----------------------:|:-------:|:--------------:|:-------------:|:-----------------------------: |:-------------------------------------------------------:|:-----:|
* | period | - | double | s | 0.02 | No | refresh period of the broadcasted values in s | default 0.02s |
* | node_name | - | string | - | - | Yes | name of the ros2 node | |
* | topic_name | - | string | - | - | Yes | name of the topic where the device must publish the data| must begin with an initial '/' |
* Parameters required by this device are shown in class: Battery_nws_ros2_ParamsParser
*
*/


class Battery_nws_ros2 :
public yarp::os::PeriodicThread,
public yarp::dev::DeviceDriver,
public yarp::dev::WrapperSingle
public yarp::dev::WrapperSingle,
Battery_nws_ros2_ParamsParser
{
public:
Battery_nws_ros2();
Expand All @@ -58,16 +55,9 @@ class Battery_nws_ros2 :


private:
// parameters from configuration
std::string m_topicName;
std::string m_nodeName;

// stamp count for timestamp
yarp::os::Stamp m_timeStamp;

// period for thread
double m_period{DEFAULT_THREAD_PERIOD};

//ros2 node
sensor_msgs::msg::BatteryState battMsg;
rclcpp::Node::SharedPtr m_node;
Expand Down
139 changes: 139 additions & 0 deletions src/devices/battery_nws_ros2/Battery_nws_ros2_ParamsParser.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,139 @@
/*
* SPDX-FileCopyrightText: 2023-2023 Istituto Italiano di Tecnologia (IIT)
* SPDX-License-Identifier: LGPL-2.1-or-later
*/


// Generated by yarpDeviceParamParserGenerator (1.0)
// This is an automatically generated file. Please do not edit it.
// It will be re-generated if the cmake flag ALLOW_DEVICE_PARAM_PARSER_GERNERATION is ON.

// Generated on: Thu Aug 1 16:19:38 2024


#include "Battery_nws_ros2_ParamsParser.h"
#include <yarp/os/LogStream.h>
#include <yarp/os/Value.h>

namespace {
YARP_LOG_COMPONENT(Battery_nws_ros2ParamsCOMPONENT, "yarp.device.Battery_nws_ros2")
}


Battery_nws_ros2_ParamsParser::Battery_nws_ros2_ParamsParser()
{
}


std::vector<std::string> Battery_nws_ros2_ParamsParser::getListOfParams() const
{
std::vector<std::string> params;
params.push_back("period");
params.push_back("node_name");
params.push_back("topic_name");
return params;
}


bool Battery_nws_ros2_ParamsParser::parseParams(const yarp::os::Searchable & config)
{
//Check for --help option
if (config.check("help"))
{
yCInfo(Battery_nws_ros2ParamsCOMPONENT) << getDocumentationOfDeviceParams();
}

std::string config_string = config.toString();
yarp::os::Property prop_check(config_string.c_str());
//Parser of parameter period
{
if (config.check("period"))
{
m_period = config.find("period").asFloat64();
yCInfo(Battery_nws_ros2ParamsCOMPONENT) << "Parameter 'period' using value:" << m_period;
}
else
{
yCInfo(Battery_nws_ros2ParamsCOMPONENT) << "Parameter 'period' using DEFAULT value:" << m_period;
}
prop_check.unput("period");
}

//Parser of parameter node_name
{
if (config.check("node_name"))
{
m_node_name = config.find("node_name").asString();
yCInfo(Battery_nws_ros2ParamsCOMPONENT) << "Parameter 'node_name' using value:" << m_node_name;
}
else
{
yCError(Battery_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'node_name' not found!";
yCError(Battery_nws_ros2ParamsCOMPONENT) << "Description of the parameter: name of the ros2 node";
return false;
}
prop_check.unput("node_name");
}

//Parser of parameter topic_name
{
if (config.check("topic_name"))
{
m_topic_name = config.find("topic_name").asString();
yCInfo(Battery_nws_ros2ParamsCOMPONENT) << "Parameter 'topic_name' using value:" << m_topic_name;
}
else
{
yCError(Battery_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'topic_name' not found!";
yCError(Battery_nws_ros2ParamsCOMPONENT) << "Description of the parameter: name of the topic where the device must publish the data";
return false;
}
prop_check.unput("topic_name");
}

/*
//This code check if the user set some parameter which are not check by the parser
//If the parser is set in strict mode, this will generate an error
if (prop_check.size() > 0)
{
bool extra_params_found = false;
for (auto it=prop_check.begin(); it!=prop_check.end(); it++)
{
if (m_parser_is_strict)
{
yCError(Battery_nws_ros2ParamsCOMPONENT) << "User asking for parameter: "<<it->name <<" which is unknown to this parser!";
extra_params_found = true;
}
else
{
yCWarning(Battery_nws_ros2ParamsCOMPONENT) << "User asking for parameter: "<< it->name <<" which is unknown to this parser!";
}
}
if (m_parser_is_strict && extra_params_found)
{
return false;
}
}
*/
return true;
}


std::string Battery_nws_ros2_ParamsParser::getDocumentationOfDeviceParams() const
{
std::string doc;
doc = doc + std::string("\n=============================================\n");
doc = doc + std::string("This is the help for device: Battery_nws_ros2\n");
doc = doc + std::string("\n");
doc = doc + std::string("This is the list of the parameters accepted by the device:\n");
doc = doc + std::string("'period': refresh period of the broadcasted values in s\n");
doc = doc + std::string("'node_name': name of the ros2 node\n");
doc = doc + std::string("'topic_name': name of the topic where the device must publish the data\n");
doc = doc + std::string("\n");
doc = doc + std::string("Here are some examples of invocation command with yarpdev, with all params:\n");
doc = doc + " yarpdev --device battery_nws_ros2 --period 0.02 --node_name <mandatory_value> --topic_name <mandatory_value>\n";
doc = doc + std::string("Using only mandatory params:\n");
doc = doc + " yarpdev --device battery_nws_ros2 --node_name <mandatory_value> --topic_name <mandatory_value>\n";
doc = doc + std::string("=============================================\n\n"); return doc;
}
75 changes: 75 additions & 0 deletions src/devices/battery_nws_ros2/Battery_nws_ros2_ParamsParser.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
/*
* SPDX-FileCopyrightText: 2023-2023 Istituto Italiano di Tecnologia (IIT)
* SPDX-License-Identifier: LGPL-2.1-or-later
*/


// Generated by yarpDeviceParamParserGenerator (1.0)
// This is an automatically generated file. Please do not edit it.
// It will be re-generated if the cmake flag ALLOW_DEVICE_PARAM_PARSER_GERNERATION is ON.

// Generated on: Thu Aug 1 16:19:38 2024


#ifndef BATTERY_NWS_ROS2_PARAMSPARSER_H
#define BATTERY_NWS_ROS2_PARAMSPARSER_H

#include <yarp/os/Searchable.h>
#include <yarp/dev/IDeviceDriverParams.h>
#include <string>
#include <cmath>

/**
* This class is the parameters parser for class Battery_nws_ros2.
*
* These are the used parameters:
* | Group name | Parameter name | Type | Units | Default Value | Required | Description | Notes |
* |:----------:|:--------------:|:------:|:-----:|:-------------:|:--------:|:--------------------------------------------------------:|:------------------------------:|
* | - | period | double | s | 0.02 | 0 | refresh period of the broadcasted values in s | default 0.02s |
* | - | node_name | string | - | - | 1 | name of the ros2 node | - |
* | - | topic_name | string | - | - | 1 | name of the topic where the device must publish the data | must begin with an initial '/' |
*
* The device can be launched by yarpdev using one of the following examples (with and without all optional parameters):
* \code{.unparsed}
* yarpdev --device battery_nws_ros2 --period 0.02 --node_name <mandatory_value> --topic_name <mandatory_value>
* \endcode
*
* \code{.unparsed}
* yarpdev --device battery_nws_ros2 --node_name <mandatory_value> --topic_name <mandatory_value>
* \endcode
*
*/

class Battery_nws_ros2_ParamsParser : public yarp::dev::IDeviceDriverParams
{
public:
Battery_nws_ros2_ParamsParser();
~Battery_nws_ros2_ParamsParser() override = default;

public:
const std::string m_device_classname = {"Battery_nws_ros2"};
const std::string m_device_name = {"battery_nws_ros2"};
bool m_parser_is_strict = false;
struct parser_version_type
{
int major = 1;
int minor = 0;
};
const parser_version_type m_parser_version = {};

const std::string m_period_defaultValue = {"0.02"};
const std::string m_node_name_defaultValue = {""};
const std::string m_topic_name_defaultValue = {""};

double m_period = {0.02};
std::string m_node_name = {}; //This default value is autogenerated. It is highly recommended to provide a suggested value also for mandatory parameters.
std::string m_topic_name = {}; //This default value is autogenerated. It is highly recommended to provide a suggested value also for mandatory parameters.

bool parseParams(const yarp::os::Searchable & config) override;
std::string getDeviceClassName() const override { return m_device_classname; }
std::string getDeviceName() const override { return m_device_name; }
std::string getDocumentationOfDeviceParams() const override;
std::vector<std::string> getListOfParams() const override;
};

#endif
3 changes: 3 additions & 0 deletions src/devices/battery_nws_ros2/Battery_nws_ros2_params.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
| | period | double | s | 0.02 | No | refresh period of the broadcasted values in s | default 0.02s |
| | node_name | string | - | - | Yes | name of the ros2 node | |
| | topic_name | string | - | - | Yes | name of the topic where the device must publish the data| must begin with an initial '/' |
3 changes: 3 additions & 0 deletions src/devices/battery_nws_ros2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,14 @@ yarp_prepare_plugin(battery_nws_ros2

if(NOT SKIP_battery_nws_ros2)
yarp_add_plugin(yarp_battery_nws_ros2)
generateDeviceParamsParser(Battery_nws_ros2 battery_nws_ros2)

target_sources(yarp_battery_nws_ros2
PRIVATE
Battery_nws_ros2.cpp
Battery_nws_ros2.h
Battery_nws_ros2_ParamsParser.h
Battery_nws_ros2_ParamsParser.cpp
)
target_sources(yarp_battery_nws_ros2 PRIVATE $<TARGET_OBJECTS:Ros2Utils>)

Expand Down

0 comments on commit 8a5280e

Please sign in to comment.