Skip to content

Commit

Permalink
Added ParamsParser to Localization2D_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 76bf4d5 commit d258a0f
Show file tree
Hide file tree
Showing 6 changed files with 257 additions and 42 deletions.
3 changes: 3 additions & 0 deletions src/devices/localization2D_nws_ros2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,14 @@ yarp_prepare_plugin(localization2D_nws_ros2

if(NOT SKIP_localization2D_nws_ros2)
yarp_add_plugin(yarp_localization2D_nws_ros2)
generateDeviceParamsParser(Localization2D_nws_ros2 localization2D_nws_ros2)

target_sources(yarp_localization2D_nws_ros2
PRIVATE
Localization2D_nws_ros2.cpp
Localization2D_nws_ros2.h
Localization2D_nws_ros2_ParamsParser.h
Localization2D_nws_ros2_ParamsParser.cpp
)
target_sources(yarp_localization2D_nws_ros2 PRIVATE $<TARGET_OBJECTS:Ros2Utils>)

Expand Down
43 changes: 6 additions & 37 deletions src/devices/localization2D_nws_ros2/Localization2D_nws_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,48 +108,17 @@ void Localization2D_nws_ros2::run()

bool Localization2D_nws_ros2::open(yarp::os::Searchable &config)
{
//wrapper params
if (config.check("ROS"))
{
Bottle& ros_group = config.findGroup("ROS");
if (!ros_group.check("parent_frame_id"))
{
yCError(LOCALIZATION2D_NWS_ROS2) << "Missing 'parent_frame_id' parameter";
//return false;
}
else
{
m_parent_frame_id = ros_group.find("parent_frame_id").asString();
}
if (!ros_group.check("child_frame_id"))
{
yCError(LOCALIZATION2D_NWS_ROS2) << "Missing 'child_frame_id' parameter";
//return false;
}
else
{
m_child_frame_id = ros_group.find("child_frame_id").asString();
}

}
else
{
}
if (!config.check("node_name")) {
yCError(LOCALIZATION2D_NWS_ROS2) << "missing node_name parameter";
return false;
}
m_nodeName = config.find("node_name").asString();
if(m_nodeName[0] == '/'){
if(m_node_name[0] == '/'){
yCError(LOCALIZATION2D_NWS_ROS2) << "node_name cannot begin with an initial /";
return false;
}
m_period = config.check("period", yarp::os::Value(0.010), "Period of the thread").asFloat64();

parseParams(config);

//create the topics
const std::string m_odom_topic ="/odom";
const std::string m_tf_topic ="/tf";
m_node = NodeCreator::createNode(m_nodeName);
m_node = NodeCreator::createNode(m_node_name);

m_publisher_odom = m_node->create_publisher<nav_msgs::msg::Odometry>(m_odom_topic, 10);
m_publisher_tf = m_node->create_publisher<tf2_msgs::msg::TFMessage>(m_tf_topic, 10);
Expand Down Expand Up @@ -180,8 +149,8 @@ void Localization2D_nws_ros2::publish_odometry_on_TF_topic()
tf2_msgs::msg::TFMessage rosData;

geometry_msgs::msg::TransformStamped tsData;
tsData.child_frame_id = m_child_frame_id;
tsData.header.frame_id = m_parent_frame_id;
tsData.child_frame_id = m_ROS_child_frame_id;
tsData.header.frame_id = m_ROS_parent_frame_id;
tsData.header.stamp = m_node->get_clock()->now(); //@@@@@@@@@@@ CHECK HERE: simulation time?
double halfYaw = m_current_odometry.odom_theta / 180.0 * M_PI * 0.5;
double cosYaw = cos(halfYaw);
Expand Down
10 changes: 5 additions & 5 deletions src/devices/localization2D_nws_ros2/Localization2D_nws_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <yarp/dev/DeviceDriver.h>
#include <yarp/os/PeriodicThread.h>
#include <yarp/os/Stamp.h>
#include "Localization2D_nws_ros2_ParamsParser.h"

#include <rclcpp/rclcpp.hpp>
#include <tf2_msgs/msg/tf_message.hpp>
Expand All @@ -24,13 +25,16 @@
*
* \brief `Localization2D_nws_ros2`: A localization server which can be wrap multiple algorithms and devices to provide robot localization in a 2D World.
*
* Parameters required by this device are shown in class: Localization2D_nws_ros2_ParamsParser
*
* Documentation to be added
*
*/
class Localization2D_nws_ros2 :
public yarp::dev::DeviceDriver,
public yarp::os::PeriodicThread,
public yarp::dev::WrapperSingle
public yarp::dev::WrapperSingle,
Localization2D_nws_ros2_ParamsParser
{
public:
Localization2D_nws_ros2();
Expand Down Expand Up @@ -62,15 +66,11 @@ class Localization2D_nws_ros2 :
rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr m_publisher_tf;
bool m_isDeviceOwned = false;

std::string m_nodeName;
std::string m_child_frame_id;
std::string m_parent_frame_id;
std::string m_robot_frame;
std::string m_fixed_frame;


double m_stats_time_last;
double m_period;
yarp::os::Stamp m_loc_stamp;
yarp::os::Stamp m_odom_stamp;

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,161 @@
/*
* 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: Fri Aug 2 15:24:54 2024


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

namespace {
YARP_LOG_COMPONENT(Localization2D_nws_ros2ParamsCOMPONENT, "yarp.device.Localization2D_nws_ros2")
}


Localization2D_nws_ros2_ParamsParser::Localization2D_nws_ros2_ParamsParser()
{
}


std::vector<std::string> Localization2D_nws_ros2_ParamsParser::getListOfParams() const
{
std::vector<std::string> params;
params.push_back("period");
params.push_back("node_name");
params.push_back("ROS::parent_frame_id");
params.push_back("ROS::child_frame_id");
return params;
}


bool Localization2D_nws_ros2_ParamsParser::parseParams(const yarp::os::Searchable & config)
{
//Check for --help option
if (config.check("help"))
{
yCInfo(Localization2D_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(Localization2D_nws_ros2ParamsCOMPONENT) << "Parameter 'period' using value:" << m_period;
}
else
{
yCInfo(Localization2D_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(Localization2D_nws_ros2ParamsCOMPONENT) << "Parameter 'node_name' using value:" << m_node_name;
}
else
{
yCError(Localization2D_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'node_name' not found!";
yCError(Localization2D_nws_ros2ParamsCOMPONENT) << "Description of the parameter: The name of the ROS2 node";
return false;
}
prop_check.unput("node_name");
}

//Parser of parameter ROS::parent_frame_id
{
yarp::os::Bottle sectionp;
sectionp = config.findGroup("ROS");
if (sectionp.check("parent_frame_id"))
{
m_ROS_parent_frame_id = sectionp.find("parent_frame_id").asString();
yCInfo(Localization2D_nws_ros2ParamsCOMPONENT) << "Parameter 'ROS::parent_frame_id' using value:" << m_ROS_parent_frame_id;
}
else
{
yCError(Localization2D_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'ROS::parent_frame_id' not found!";
yCError(Localization2D_nws_ros2ParamsCOMPONENT) << "Description of the parameter: The name of the odom data parent frame";
return false;
}
prop_check.unput("ROS::parent_frame_id");
}

//Parser of parameter ROS::child_frame_id
{
yarp::os::Bottle sectionp;
sectionp = config.findGroup("ROS");
if (sectionp.check("child_frame_id"))
{
m_ROS_child_frame_id = sectionp.find("child_frame_id").asString();
yCInfo(Localization2D_nws_ros2ParamsCOMPONENT) << "Parameter 'ROS::child_frame_id' using value:" << m_ROS_child_frame_id;
}
else
{
yCError(Localization2D_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'ROS::child_frame_id' not found!";
yCError(Localization2D_nws_ros2ParamsCOMPONENT) << "Description of the parameter: The name of the odom data child frame";
return false;
}
prop_check.unput("ROS::child_frame_id");
}

/*
//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(Localization2D_nws_ros2ParamsCOMPONENT) << "User asking for parameter: "<<it->name <<" which is unknown to this parser!";
extra_params_found = true;
}
else
{
yCWarning(Localization2D_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 Localization2D_nws_ros2_ParamsParser::getDocumentationOfDeviceParams() const
{
std::string doc;
doc = doc + std::string("\n=============================================\n");
doc = doc + std::string("This is the help for device: Localization2D_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': The PeriodicThread period in seconds\n");
doc = doc + std::string("'node_name': The name of the ROS2 node\n");
doc = doc + std::string("'ROS::parent_frame_id': The name of the odom data parent frame\n");
doc = doc + std::string("'ROS::child_frame_id': The name of the odom data child frame\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 localization2D_nws_ros2 --period 0.01 --node_name <mandatory_value> --ROS::parent_frame_id <mandatory_value> --ROS::child_frame_id <mandatory_value>\n";
doc = doc + std::string("Using only mandatory params:\n");
doc = doc + " yarpdev --device localization2D_nws_ros2 --node_name <mandatory_value> --ROS::parent_frame_id <mandatory_value> --ROS::child_frame_id <mandatory_value>\n";
doc = doc + std::string("=============================================\n\n"); return doc;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
/*
* 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: Fri Aug 2 15:24:54 2024


#ifndef LOCALIZATION2D_NWS_ROS2_PARAMSPARSER_H
#define LOCALIZATION2D_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 Localization2D_nws_ros2.
*
* These are the used parameters:
* | Group name | Parameter name | Type | Units | Default Value | Required | Description | Notes |
* |:----------:|:---------------:|:------:|:-------:|:-------------:|:--------:|:--------------------------------------:|:-----:|
* | - | period | double | seconds | 0.01 | 0 | The PeriodicThread period in seconds | - |
* | - | node_name | string | - | - | 1 | The name of the ROS2 node | - |
* | ROS | parent_frame_id | string | - | - | 1 | The name of the odom data parent frame | - |
* | ROS | child_frame_id | string | - | - | 1 | The name of the odom data child frame | - |
*
* The device can be launched by yarpdev using one of the following examples (with and without all optional parameters):
* \code{.unparsed}
* yarpdev --device localization2D_nws_ros2 --period 0.01 --node_name <mandatory_value> --ROS::parent_frame_id <mandatory_value> --ROS::child_frame_id <mandatory_value>
* \endcode
*
* \code{.unparsed}
* yarpdev --device localization2D_nws_ros2 --node_name <mandatory_value> --ROS::parent_frame_id <mandatory_value> --ROS::child_frame_id <mandatory_value>
* \endcode
*
*/

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

public:
const std::string m_device_classname = {"Localization2D_nws_ros2"};
const std::string m_device_name = {"localization2D_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.01"};
const std::string m_node_name_defaultValue = {""};
const std::string m_ROS_parent_frame_id_defaultValue = {""};
const std::string m_ROS_child_frame_id_defaultValue = {""};

double m_period = {0.01};
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_ROS_parent_frame_id = {}; //This default value is autogenerated. It is highly recommended to provide a suggested value also for mandatory parameters.
std::string m_ROS_child_frame_id = {}; //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,4 @@
| | period | double | seconds | 0.01 | No | The PeriodicThread period in seconds |
| | node_name | string | - | - | Yes | The name of the ROS2 node |
| ROS | parent_frame_id | string | - | - | Yes | The name of the odom data parent frame |
| ROS | child_frame_id | string | - | - | Yes | The name of the odom data child frame |

0 comments on commit d258a0f

Please sign in to comment.