Skip to content

Commit

Permalink
Added ParamsParser to Odometry2D_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 28, 2024
1 parent 509a1d6 commit a6b0de7
Show file tree
Hide file tree
Showing 6 changed files with 279 additions and 57 deletions.
3 changes: 3 additions & 0 deletions src/devices/odometry2D_nws_ros2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,14 @@ yarp_prepare_plugin(odometry2D_nws_ros2

if(NOT SKIP_odometry2D_nws_ros2)
yarp_add_plugin(yarp_odometry2D_nws_ros2)
generateDeviceParamsParser(Odometry2D_nws_ros2 odometry2D_nws_ros2)

target_sources(yarp_odometry2D_nws_ros2
PRIVATE
Odometry2D_nws_ros2.cpp
Odometry2D_nws_ros2.h
Odometry2D_nws_ros2_ParamsParser.h
Odometry2D_nws_ros2_ParamsParser.cpp
)
target_sources(yarp_odometry2D_nws_ros2 PRIVATE $<TARGET_OBJECTS:Ros2Utils>)

Expand Down
49 changes: 10 additions & 39 deletions src/devices/odometry2D_nws_ros2/Odometry2D_nws_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,51 +64,22 @@ bool Odometry2D_nws_ros2::threadInit()

bool Odometry2D_nws_ros2::open(yarp::os::Searchable &config)
{
if (!config.check("period")) {
yCWarning(ODOMETRY2D_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(ODOMETRY2D_NWS_ROS2) << "missing node_name parameter";
return false;
}
m_nodeName = config.find("node_name").asString();
if (m_nodeName[0] == '/') {
parseParams(config);
if (m_node_name[0] == '/') {
yCError(ODOMETRY2D_NWS_ROS2) << "node_name parameter cannot begin with '/'";
return false;
}

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

if (!config.check("odom_frame")) {
yCError(ODOMETRY2D_NWS_ROS2) << "missing odom_frame parameter";
return false;
}
m_odomFrame = config.find("odom_frame").asString();


if (!config.check("base_frame")) {
yCError(ODOMETRY2D_NWS_ROS2) << "missing base_frame parameter";
return false;
}
m_baseFrame = config.find("base_frame").asString();

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(ODOMETRY2D_NWS_ROS2) << " opening " << m_nodeName << " Node, check your yarp-ROS2 network configuration\n";
yCError(ODOMETRY2D_NWS_ROS2) << " opening " << m_node_name << " Node, check your yarp-ROS2 network configuration\n";
return false;
}

Expand All @@ -117,7 +88,7 @@ bool Odometry2D_nws_ros2::open(yarp::os::Searchable &config)
const std::string m_tf_topic ="/tf";
m_publisher_tf = m_node->create_publisher<tf2_msgs::msg::TFMessage>(m_tf_topic, 10);

m_ros2Publisher_odometry = m_node->create_publisher<nav_msgs::msg::Odometry>(m_topicName, 10);
m_ros2Publisher_odometry = m_node->create_publisher<nav_msgs::msg::Odometry>(m_topic_name, 10);

yCInfo(ODOMETRY2D_NWS_ROS2) << "Waiting for device to attach";
return true;
Expand Down Expand Up @@ -145,8 +116,8 @@ void Odometry2D_nws_ros2::run()
}

nav_msgs::msg::Odometry odometryMsg;
odometryMsg.header.frame_id = m_odomFrame;
odometryMsg.child_frame_id = m_baseFrame;
odometryMsg.header.frame_id = m_odom_frame;
odometryMsg.child_frame_id = m_base_frame;

odometryMsg.pose.pose.position.x = odometryData.odom_x;
odometryMsg.pose.pose.position.y = odometryData.odom_y;
Expand All @@ -171,8 +142,8 @@ void Odometry2D_nws_ros2::run()
tf2_msgs::msg::TFMessage rosData;

geometry_msgs::msg::TransformStamped tsData;
tsData.child_frame_id = m_baseFrame;
tsData.header.frame_id = m_odomFrame;
tsData.child_frame_id = m_base_frame;
tsData.header.frame_id = m_odom_frame;

tsData.transform.rotation.x = 0;
tsData.transform.rotation.y = 0;
Expand Down
23 changes: 5 additions & 18 deletions src/devices/odometry2D_nws_ros2/Odometry2D_nws_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#include <yarp/dev/WrapperSingle.h>
#include <tf2_msgs/msg/tf_message.hpp>

#include "Odometry2D_nws_ros2_ParamsParser.h"

#ifndef _USE_MATH_DEFINES
#define _USE_MATH_DEFINES
#endif
Expand All @@ -29,14 +31,7 @@
* \brief `Odometry2D_nws_ros2`: A ros2 nws to get odometry and publish it on a ros2 topic.
* The attached device must implement a `yarp::dev::Nav2D::IOdometry2D` 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 '/' |
* | odom_frame | - | string | - | - | Yes | name of the reference frame for odometry | |
* | base_frame | - | string | - | - | Yes | name of the base frame for odometry | |
* Parameters required by this device are shown in class: `Odometry2D_nws_ros2_ParamsParser`.
*
* Example of configuration file using .ini format.
*
Expand Down Expand Up @@ -87,7 +82,8 @@
class Odometry2D_nws_ros2 :
public yarp::os::PeriodicThread,
public yarp::dev::DeviceDriver,
public yarp::dev::WrapperSingle
public yarp::dev::WrapperSingle,
Odometry2D_nws_ros2_ParamsParser
{
public:
Odometry2D_nws_ros2();
Expand All @@ -108,18 +104,9 @@ class Odometry2D_nws_ros2 :


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

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

// period for thread
double m_period{DEFAULT_THREAD_PERIOD};

//ros2 node
rclcpp::Node::SharedPtr m_node;
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr m_ros2Publisher_odometry;
Expand Down
175 changes: 175 additions & 0 deletions src/devices/odometry2D_nws_ros2/Odometry2D_nws_ros2_ParamsParser.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,175 @@
/*
* 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: Wed Aug 28 15:28:34 2024


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

namespace {
YARP_LOG_COMPONENT(Odometry2D_nws_ros2ParamsCOMPONENT, "yarp.device.Odometry2D_nws_ros2")
}


Odometry2D_nws_ros2_ParamsParser::Odometry2D_nws_ros2_ParamsParser()
{
}


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


bool Odometry2D_nws_ros2_ParamsParser::parseParams(const yarp::os::Searchable & config)
{
//Check for --help option
if (config.check("help"))
{
yCInfo(Odometry2D_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(Odometry2D_nws_ros2ParamsCOMPONENT) << "Parameter 'period' using value:" << m_period;
}
else
{
yCInfo(Odometry2D_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(Odometry2D_nws_ros2ParamsCOMPONENT) << "Parameter 'node_name' using value:" << m_node_name;
}
else
{
yCError(Odometry2D_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'node_name' not found!";
yCError(Odometry2D_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(Odometry2D_nws_ros2ParamsCOMPONENT) << "Parameter 'topic_name' using value:" << m_topic_name;
}
else
{
yCError(Odometry2D_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'topic_name' not found!";
yCError(Odometry2D_nws_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 odom_frame
{
if (config.check("odom_frame"))
{
m_odom_frame = config.find("odom_frame").asString();
yCInfo(Odometry2D_nws_ros2ParamsCOMPONENT) << "Parameter 'odom_frame' using value:" << m_odom_frame;
}
else
{
yCError(Odometry2D_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'odom_frame' not found!";
yCError(Odometry2D_nws_ros2ParamsCOMPONENT) << "Description of the parameter: name of the reference frame for odometry";
return false;
}
prop_check.unput("odom_frame");
}

//Parser of parameter base_frame
{
if (config.check("base_frame"))
{
m_base_frame = config.find("base_frame").asString();
yCInfo(Odometry2D_nws_ros2ParamsCOMPONENT) << "Parameter 'base_frame' using value:" << m_base_frame;
}
else
{
yCError(Odometry2D_nws_ros2ParamsCOMPONENT) << "Mandatory parameter 'base_frame' not found!";
yCError(Odometry2D_nws_ros2ParamsCOMPONENT) << "Description of the parameter: name of the base frame for odometry";
return false;
}
prop_check.unput("base_frame");
}

/*
//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(Odometry2D_nws_ros2ParamsCOMPONENT) << "User asking for parameter: "<<it->name <<" which is unknown to this parser!";
extra_params_found = true;
}
else
{
yCWarning(Odometry2D_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 Odometry2D_nws_ros2_ParamsParser::getDocumentationOfDeviceParams() const
{
std::string doc;
doc = doc + std::string("\n=============================================\n");
doc = doc + std::string("This is the help for device: Odometry2D_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("'odom_frame': name of the reference frame for odometry\n");
doc = doc + std::string("'base_frame': name of the base frame for odometry\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 odometry2D_nws_ros2 --period 0.02 --node_name <mandatory_value> --topic_name <mandatory_value> --odom_frame <mandatory_value> --base_frame <mandatory_value>\n";
doc = doc + std::string("Using only mandatory params:\n");
doc = doc + " yarpdev --device odometry2D_nws_ros2 --node_name <mandatory_value> --topic_name <mandatory_value> --odom_frame <mandatory_value> --base_frame <mandatory_value>\n";
doc = doc + std::string("=============================================\n\n"); return doc;
}
Loading

0 comments on commit a6b0de7

Please sign in to comment.