Skip to content

Commit

Permalink
Added ParamsParser to MultipleAnalogSensors_nwc_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 d0cffc7 commit 5c0aaf5
Show file tree
Hide file tree
Showing 7 changed files with 240 additions and 44 deletions.
3 changes: 3 additions & 0 deletions src/devices/multipleAnalogSensors_nwc_ros2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,15 @@ yarp_prepare_plugin(imu_nwc_ros2

if(ENABLE_imu_nwc_ros2)
yarp_add_plugin(yarp_imu_nwc_ros2)
generateDeviceParamsParser(GenericSensor_nwc_ros2 genericSensor_nwc_ros2)

target_sources(yarp_imu_nwc_ros2
PRIVATE
Imu_nwc_ros2.cpp
Imu_nwc_ros2.h
GenericSensor_nwc_ros2.h
GenericSensor_nwc_ros2_ParamsParser.h
GenericSensor_nwc_ros2_ParamsParser.cpp
)

target_link_libraries(yarp_imu_nwc_ros2
Expand Down
48 changes: 13 additions & 35 deletions src/devices/multipleAnalogSensors_nwc_ros2/GenericSensor_nwc_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <yarp/os/LogComponent.h>
#include <yarp/os/LogStream.h>
#include <mutex>
#include "GenericSensor_nwc_ros2_ParamsParser.h"

#include <rclcpp/rclcpp.hpp>
#include <Ros2Utils.h>
Expand All @@ -33,25 +34,19 @@ YARP_DECLARE_LOG_COMPONENT(GENERICSENSOR_NWC_ROS2)
* |:-----------------:|
* | `genericSensor_nwc_ros2` |
*
* The parameters accepted by this device are:
* | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes |
* |:--------------:|:--------------:|:-------:|:--------------:|:----------------:|:--------------------------: |:-----------------------------------------------------------------:|:-------------------------------:|
* | topic_name | - | string | - | - | Yes | The name of the ROS topic opened by this device. | MUST start with a '/' character |
* | node_name | - | string | - | - | Yes | The name of the ROS node opened by this device | Autogenerated by default |
* | sensor_name | - | string | - | - | Yes | The name of the sensor the data are coming from | |
* The parameters accepted by this device are shown in class: GenericSensor_nwc_ros2_ParamsParser
*
*/

template <class ROS_MSG>
class GenericSensor_nwc_ros2 :
public yarp::dev::DeviceDriver
public yarp::dev::DeviceDriver,
protected GenericSensor_nwc_ros2_ParamsParser
{
protected:
double m_periodInS{0.01};
double m_timestamp;
std::string m_subscriptionName;
std::string m_rosNodeName;
std::string m_framename;
std::string m_sensorName;
Ros2Spinner* m_spinner{nullptr};
const size_t m_sens_index = 0;
mutable std::mutex m_dataMutex;
Expand Down Expand Up @@ -85,48 +80,31 @@ GenericSensor_nwc_ros2<ROS_MSG>::~GenericSensor_nwc_ros2() = default;
template <class ROS_MSG>
bool GenericSensor_nwc_ros2<ROS_MSG>::open(yarp::os::Searchable & config)
{
if (!config.check("topic_name")) {
yCError(GENERICSENSOR_NWC_ROS2, "Missing topic_name parameter, exiting.");
return false;
}

if (!config.check("node_name"))
{
yCError(GENERICSENSOR_NWC_ROS2) << "Missing node_name parameter";
return false;
}

if (!config.check("sensor_name")) {
yCError(GENERICSENSOR_NWC_ROS2, "Missing sensor_name parameter, exiting.");
return false;
}

m_rosNodeName = config.find("node_name").asString();
if (m_rosNodeName.c_str()[0] == '/') {
parseParams(config);
if (m_node_name.c_str()[0] == '/') {
yCError(GENERICSENSOR_NWC_ROS2) << "node name cannot begin with /";
return false;
}

m_subscriptionName = config.find("topic_name").asString();
if (m_subscriptionName.c_str()[0] != '/') {
if (m_topic_name.c_str()[0] != '/') {
yCError(GENERICSENSOR_NWC_ROS2) << "Missing '/' in topic_name parameter";
return false;
}

m_sensorName = config.find("sensor_name").asString();
m_sensor_name = config.find("sensor_name").asString();

m_node = NodeCreator::createNode(m_rosNodeName);
m_subscription = m_node->create_subscription<ROS_MSG>(m_subscriptionName, rclcpp::QoS(10),
m_node = NodeCreator::createNode(m_node_name);
m_subscription = m_node->create_subscription<ROS_MSG>(m_topic_name, rclcpp::QoS(10),
std::bind(&GenericSensor_nwc_ros2<ROS_MSG>::subscription_callback,
this, std::placeholders::_1));

if (m_node == nullptr) {
yCError(GENERICSENSOR_NWC_ROS2) << "Opening " << m_rosNodeName << " Node creation failed, check your yarp-ROS network configuration\n";
yCError(GENERICSENSOR_NWC_ROS2) << "Opening " << m_node_name << " Node creation failed, check your yarp-ROS network configuration\n";
return false;
}

if (m_subscription == nullptr) {
yCError(GENERICSENSOR_NWC_ROS2) << "Opening " << m_subscriptionName << " Topic failed, check your yarp-ROS network configuration\n";
yCError(GENERICSENSOR_NWC_ROS2) << "Opening " << m_topic_name << " Topic failed, check your yarp-ROS network configuration\n";
return false;
}

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,141 @@
/*
* 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: Mon Aug 5 16:25:52 2024


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

namespace {
YARP_LOG_COMPONENT(GenericSensor_nwc_ros2ParamsCOMPONENT, "yarp.device.GenericSensor_nwc_ros2")
}


GenericSensor_nwc_ros2_ParamsParser::GenericSensor_nwc_ros2_ParamsParser()
{
}


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


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

std::string config_string = config.toString();
yarp::os::Property prop_check(config_string.c_str());
//Parser of parameter node_name
{
if (config.check("node_name"))
{
m_node_name = config.find("node_name").asString();
yCInfo(GenericSensor_nwc_ros2ParamsCOMPONENT) << "Parameter 'node_name' using value:" << m_node_name;
}
else
{
yCError(GenericSensor_nwc_ros2ParamsCOMPONENT) << "Mandatory parameter 'node_name' not found!";
yCError(GenericSensor_nwc_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(GenericSensor_nwc_ros2ParamsCOMPONENT) << "Parameter 'topic_name' using value:" << m_topic_name;
}
else
{
yCError(GenericSensor_nwc_ros2ParamsCOMPONENT) << "Mandatory parameter 'topic_name' not found!";
yCError(GenericSensor_nwc_ros2ParamsCOMPONENT) << "Description of the parameter: name of the topic where the device must publish the data";
return false;
}
prop_check.unput("topic_name");
}

//Parser of parameter sensor_name
{
if (config.check("sensor_name"))
{
m_sensor_name = config.find("sensor_name").asString();
yCInfo(GenericSensor_nwc_ros2ParamsCOMPONENT) << "Parameter 'sensor_name' using value:" << m_sensor_name;
}
else
{
yCError(GenericSensor_nwc_ros2ParamsCOMPONENT) << "Mandatory parameter 'sensor_name' not found!";
yCError(GenericSensor_nwc_ros2ParamsCOMPONENT) << "Description of the parameter: The name of the sensor the data are coming from";
return false;
}
prop_check.unput("sensor_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(GenericSensor_nwc_ros2ParamsCOMPONENT) << "User asking for parameter: "<<it->name <<" which is unknown to this parser!";
extra_params_found = true;
}
else
{
yCWarning(GenericSensor_nwc_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 GenericSensor_nwc_ros2_ParamsParser::getDocumentationOfDeviceParams() const
{
std::string doc;
doc = doc + std::string("\n=============================================\n");
doc = doc + std::string("This is the help for device: GenericSensor_nwc_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("'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("'sensor_name': The name of the sensor the data are coming from\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 genericSensor_nwc_ros2 --node_name <mandatory_value> --topic_name <mandatory_value> --sensor_name <mandatory_value>\n";
doc = doc + std::string("Using only mandatory params:\n");
doc = doc + " yarpdev --device genericSensor_nwc_ros2 --node_name <mandatory_value> --topic_name <mandatory_value> --sensor_name <mandatory_value>\n";
doc = doc + std::string("=============================================\n\n"); return doc;
}
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: Mon Aug 5 16:25:52 2024


#ifndef GENERICSENSOR_NWC_ROS2_PARAMSPARSER_H
#define GENERICSENSOR_NWC_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 GenericSensor_nwc_ros2.
*
* These are the used parameters:
* | Group name | Parameter name | Type | Units | Default Value | Required | Description | Notes |
* |:----------:|:--------------:|:------:|:-----:|:-------------:|:--------:|:--------------------------------------------------------:|:----------------------------------:|
* | - | node_name | string | - | - | 1 | name of the ros2 node | must not start with an initial '/' |
* | - | topic_name | string | - | - | 1 | name of the topic where the device must publish the data | must begin with an initial '/' |
* | - | sensor_name | string | - | - | 1 | The name of the sensor the data are coming from | - |
*
* The device can be launched by yarpdev using one of the following examples (with and without all optional parameters):
* \code{.unparsed}
* yarpdev --device genericSensor_nwc_ros2 --node_name <mandatory_value> --topic_name <mandatory_value> --sensor_name <mandatory_value>
* \endcode
*
* \code{.unparsed}
* yarpdev --device genericSensor_nwc_ros2 --node_name <mandatory_value> --topic_name <mandatory_value> --sensor_name <mandatory_value>
* \endcode
*
*/

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

public:
const std::string m_device_classname = {"GenericSensor_nwc_ros2"};
const std::string m_device_name = {"genericSensor_nwc_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_node_name_defaultValue = {""};
const std::string m_topic_name_defaultValue = {""};
const std::string m_sensor_name_defaultValue = {""};

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.
std::string m_sensor_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
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
| | node_name | string | - | - | Yes | name of the ros2 node | must not start with an initial '/' |
| | topic_name | string | - | - | Yes | name of the topic where the device must publish the data | must begin with an initial '/' |
| | sensor_name | string | - | - | Yes | The name of the sensor the data are coming from | |
6 changes: 3 additions & 3 deletions src/devices/multipleAnalogSensors_nwc_ros2/Imu_nwc_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ bool Imu_nwc_ros2::getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yar
bool Imu_nwc_ros2::getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const
{
YARP_UNUSED(sens_index);
name = m_sensorName;
name = m_sensor_name;

return true;
}
Expand Down Expand Up @@ -107,7 +107,7 @@ bool Imu_nwc_ros2::getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Ve
bool Imu_nwc_ros2::getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const
{
YARP_UNUSED(sens_index);
name = m_sensorName;
name = m_sensor_name;

return true;
}
Expand Down Expand Up @@ -173,7 +173,7 @@ bool Imu_nwc_ros2::getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index,
bool Imu_nwc_ros2::getOrientationSensorName(size_t sens_index, std::string &name) const
{
YARP_UNUSED(sens_index);
name = m_sensorName;
name = m_sensor_name;

return true;
}
Expand Down
8 changes: 2 additions & 6 deletions src/devices/multipleAnalogSensors_nwc_ros2/Imu_nwc_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,8 @@
* |:-----------------:|
* | `Imu_nwc_ros2` |
*
* The parameters accepted by this device are:
* | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes |
* |:--------------:|:--------------:|:-------:|:--------------:|:----------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:|
* | topic_name | - | string | - | - | Yes | The name of the ROS topic opened by this device. | MUST start with a '/' character |
* | node_name | - | string | - | - | Yes | The name of the ROS node opened by this device | Autogenerated by default |
* | sensor_name | - | string | - | - | Yes | The name of the sensor the data are coming from | |
* The parameters accepted by this device are shown in class: GenericSensor_nwc_ros2_ParamsParser
*
*/
class Imu_nwc_ros2 : public GenericSensor_nwc_ros2<sensor_msgs::msg::Imu>,
public yarp::dev::IThreeAxisLinearAccelerometers,
Expand Down

0 comments on commit 5c0aaf5

Please sign in to comment.