Skip to content

Commit

Permalink
added check_style script to CI
Browse files Browse the repository at this point in the history
  • Loading branch information
randaz81 committed Aug 16, 2022
1 parent efd8f46 commit 813ab27
Show file tree
Hide file tree
Showing 22 changed files with 257 additions and 39 deletions.
17 changes: 17 additions & 0 deletions .github/workflows/conda-ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,23 @@ on:
- cron: '0 2 * * *'

jobs:

check-style:
name: 'Check Style'
runs-on: ubuntu-20.04
steps:
- name: Clone repository
uses: actions/checkout@v2

- name: Install Dependencies
run: |
sudo apt-get update -qq
sudo apt-get install -qq -y perl
- name: Check Style
run: |
perl tests/misc/check_style.pl
build:
name: '[${{ matrix.os }}@${{ matrix.build_type }}@${{ matrix.ros_distro }}@conda]'
runs-on: ${{ matrix.os }}
Expand Down
2 changes: 1 addition & 1 deletion cmake/FindTinyXML2.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ if(TinyXML2_FOUND)
if(NOT EXISTS ${TINYXML2_LIBRARY_PATH})
message(FATAL_ERROR "library file path ${TINYXML2_LIBRARY_PATH} does not exist")
endif()

add_library(tinyxml2::tinyxml2 UNKNOWN IMPORTED)
set_property(TARGET tinyxml2::tinyxml2 PROPERTY IMPORTED_LOCATION ${TINYXML2_LIBRARY_PATH})
set_property(TARGET tinyxml2::tinyxml2 PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${TINYXML2_INCLUDE_DIR})
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>yarp-ros2</name>
<name>yarp-devices-ros2</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">root</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ void FrameTransformSet_nwc_ros2::yarpTransformToROS2Transform(const yarp::math::
geometry_msgs::msg::Transform tempTf;
geometry_msgs::msg::Vector3 tempTransl;
geometry_msgs::msg::Quaternion tempRotation;

tempTransl.x = input.translation.tX;
tempTransl.y = input.translation.tY;
tempTransl.z = input.translation.tY;
Expand All @@ -167,7 +167,7 @@ void FrameTransformSet_nwc_ros2::yarpTransformToROS2Transform(const yarp::math::
ros2TimeFromYarp(input.isStatic ? yarp::os::Time::now() : input.timestamp,tempStamp);
tempHeader.stamp = tempStamp;
tempHeader.frame_id = input.src_frame_id;

output.header = tempHeader;
output.child_frame_id = input.dst_frame_id;
output.transform = tempTf;
Expand Down
20 changes: 10 additions & 10 deletions src/devices/localization2D_nws_ros2/Localization2D_nws_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ bool Localization2D_nws_ros2::attach(yarp::dev::PolyDriver* poly)
yCError(LOCALIZATION2D_NWS_ROS2, "Subdevice passed to attach method is invalid");
return false;
}

return true;
}

Expand All @@ -62,7 +62,7 @@ bool Localization2D_nws_ros2::detach()

void Localization2D_nws_ros2::run()
{
double m_stats_time_curr = yarp::os::Time::now();
double m_stats_time_curr = yarp::os::Time::now();
if (m_stats_time_curr - m_stats_time_last > 5.0)
{
yCInfo(LOCALIZATION2D_NWS_ROS2) << "Running";
Expand Down Expand Up @@ -102,9 +102,9 @@ void Localization2D_nws_ros2::run()
{
yCWarning(LOCALIZATION2D_NWS_ROS2, "The system is not properly localized!");
}
if (1) publish_odometry_on_ROS_topic();
if (1) publish_odometry_on_TF_topic();

if (1) publish_odometry_on_ROS_topic();
if (1) publish_odometry_on_TF_topic();
}
}

Expand All @@ -129,7 +129,7 @@ bool Localization2D_nws_ros2::open(yarp::os::Searchable &config)
}
m_isDeviceOwned = true;
}

//wrapper params
if (config.check("ROS"))
{
Expand All @@ -156,7 +156,7 @@ bool Localization2D_nws_ros2::open(yarp::os::Searchable &config)
}
else
{
}
}
if (!config.check("node_name")) {
yCError(LOCALIZATION2D_NWS_ROS2) << "missing node_name parameter";
return false;
Expand All @@ -167,7 +167,7 @@ bool Localization2D_nws_ros2::open(yarp::os::Searchable &config)
return false;
}
m_period = config.check("period", yarp::os::Value(0.010), "Period of the thread").asFloat64();

//create the topics
const std::string m_odom_topic ="/odom";
const std::string m_tf_topic ="/tf";
Expand All @@ -176,7 +176,7 @@ bool Localization2D_nws_ros2::open(yarp::os::Searchable &config)
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);
yCInfo(LOCALIZATION2D_NWS_ROS2, "Opened topics: %s, %s", m_odom_topic.c_str(), m_tf_topic.c_str());

//start the publishig thread
setPeriod(m_period);
start();
Expand Down Expand Up @@ -206,7 +206,7 @@ void Localization2D_nws_ros2::publish_odometry_on_TF_topic()
tsData.transform.translation.x = m_current_odometry.odom_x;
tsData.transform.translation.y = m_current_odometry.odom_y;
tsData.transform.translation.z = 0;

if (rosData.transforms.size() == 0)
{
rosData.transforms.push_back(tsData);
Expand Down
12 changes: 6 additions & 6 deletions src/devices/localization2D_nws_ros2/Localization2D_nws_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,10 @@ class Localization2D_nws_ros2 :
Localization2D_nws_ros2& operator=(const Localization2D_nws_ros2&) = delete;
Localization2D_nws_ros2& operator=(Localization2D_nws_ros2&&) noexcept = delete;
~Localization2D_nws_ros2() override = default;

bool attach(yarp::dev::PolyDriver* poly) override;
bool detach() override;

// DeviceDriver
bool open(yarp::os::Searchable& config) override;
bool close() override;
Expand All @@ -56,22 +56,22 @@ class Localization2D_nws_ros2 :
private:
void publish_odometry_on_ROS_topic();
void publish_odometry_on_TF_topic();

private:
yarp::dev::PolyDriver m_driver;
yarp::dev::Nav2D::ILocalization2D *m_iLoc = nullptr;
rclcpp::Node::SharedPtr m_node;
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr m_publisher_odom;
rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr m_publisher_tf;
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;
Expand Down
Empty file modified src/devices/map2D_nws_ros2/CMakeLists.txt
100755 → 100644
Empty file.
Empty file modified src/devices/map2D_nws_ros2/Map2D_nws_ros2.cpp
100755 → 100644
Empty file.
2 changes: 1 addition & 1 deletion src/devices/map2D_nws_ros2/Map2D_nws_ros2.h
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ class Map2D_nws_ros2 :
public:
Map2D_nws_ros2();
~Map2D_nws_ros2() override = default;


//IMultipleWrapper
bool attach(yarp::dev::PolyDriver* driver) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,4 +116,4 @@ void MobileBaseVelocityControl_nws_ros2::run()
{
yCInfo(MOBVEL_NWS_ROS2, "starting");
rclcpp::spin(m_node);
}
}
12 changes: 6 additions & 6 deletions src/devices/rangefinder2D_nws_ros2/Rangefinder2D_nws_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ bool Rangefinder2D_nws_ros2::attach(yarp::dev::PolyDriver* driver)
yCError(RANGEFINDER2D_NWS_ROS2) << "Laser device does not provide horizontal resolution ";
return false;
}

return true;
}

Expand All @@ -83,7 +83,7 @@ bool Rangefinder2D_nws_ros2::detach()
void Rangefinder2D_nws_ros2::run()
{
auto message = std_msgs::msg::String();

if (m_iDevice!=nullptr)
{
bool ret = true;
Expand All @@ -92,7 +92,7 @@ void Rangefinder2D_nws_ros2::run()
double synchronized_timestamp = 0;
ret &= m_iDevice->getRawData(ranges, &synchronized_timestamp);
ret &= m_iDevice->getDeviceStatus(status);

if (ret)
{
int ranges_size = ranges.size();
Expand Down Expand Up @@ -167,19 +167,19 @@ bool Rangefinder2D_nws_ros2::open(yarp::os::Searchable &config)
}
m_isDeviceOwned = true;
}

//wrapper params
m_topic = config.check("topic_name", yarp::os::Value("laser_topic"), "Name of the ROS2 topic").asString();
m_frame_id = config.check("frame_id", yarp::os::Value("laser_frame"), "Name of the frameId").asString();
m_node_name = config.check("node_name", yarp::os::Value("laser_node"), "Name of the node").asString();
m_period = config.check("period", yarp::os::Value(0.010), "Period of the thread").asFloat64();

//create the topic

m_node = NodeCreator::createNode(m_node_name);
m_publisher = m_node->create_publisher<sensor_msgs::msg::LaserScan>(m_topic, 10);
yCInfo(RANGEFINDER2D_NWS_ROS2, "Opened topic: %s", m_topic.c_str());

//start the publishig thread
setPeriod(m_period);
start();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class Rangefinder2D_nws_ros2 :
//WrapperSingle
bool attach(yarp::dev::PolyDriver* driver) override;
bool detach() override;

// DeviceDriver
bool open(yarp::os::Searchable& config) override;
bool close() override;
Expand Down
2 changes: 1 addition & 1 deletion src/devices/rgbdSensor_nwc_ros2/RgbdSensor_nwc_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -448,4 +448,4 @@ std::string RgbdSensor_nwc_ros2::getLastErrorMsg(yarp::os::Stamp* timeStamp)
{
yCError(RGBDSENSOR_NWC_ROS2) << "get last error not yet implemented";
return "get last error not yet implemented";
}
}
6 changes: 3 additions & 3 deletions src/devices/rgbdSensor_nwc_ros2/RgbdSensor_nwc_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ class RgbdSensor_nwc_ros2:
std::string m_ros2_node_name;

// yarp variables
int m_verbose{2};
int m_verbose{2};

//ros2 node and subscribers
Ros2Subscriber<RgbdSensor_nwc_ros2, sensor_msgs::msg::CameraInfo>* sub1;
Expand Down Expand Up @@ -178,8 +178,8 @@ class RgbdSensor_nwc_ros2:
void color_raw_callback(const sensor_msgs::msg::Image::SharedPtr msg);
void color_info_callback(const sensor_msgs::msg::CameraInfo::SharedPtr msg);

yarp::dev::IRGBDSensor::RGBDSensor_status getSensorStatus() override;
std::string getLastErrorMsg(yarp::os::Stamp* timeStamp = NULL) override;
yarp::dev::IRGBDSensor::RGBDSensor_status getSensorStatus() override;
std::string getLastErrorMsg(yarp::os::Stamp* timeStamp = NULL) override;
};


Expand Down
2 changes: 1 addition & 1 deletion src/devices/ros2RGBDConversionUtils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ target_sources(Ros2RGBDConversionUtils PRIVATE
Ros2RGBDConversionUtils.h
ros2PixelCode.h
ros2PixelCode.cpp)

target_include_directories(Ros2RGBDConversionUtils PUBLIC ${CMAKE_CURRENT_LIST_DIR})

target_link_libraries(Ros2RGBDConversionUtils PRIVATE YARP::YARP_os
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ void yarp::dev::Ros2RGBDConversionUtils::convertDepthImageRos2ToYarpImageOf(sens
}


void yarp::dev::Ros2RGBDConversionUtils::updateStamp( sensor_msgs::msg::CameraInfo::SharedPtr ros_camera_info_src,
void yarp::dev::Ros2RGBDConversionUtils::updateStamp( sensor_msgs::msg::CameraInfo::SharedPtr ros_camera_info_src,
std::string& frame_id_dest,
yarp::os::Stamp& yarp_stamp)
{
Expand Down Expand Up @@ -128,4 +128,3 @@ void yarp::dev::Ros2RGBDConversionUtils::deepCopyImageOf(const DepthImage& src,
dest.getRawImage()[it] = src.getRawImage()[it];
}
}

Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ namespace yarp {

void deepCopyImageOf(const DepthImage& src, DepthImage& dest);
} // namespace Ros2RGBDConversionUtils
} // namespace dev
} // namespace dev
} // namespace yarp

#endif //ROS2_RGBD_CONVERSION_UTILS_H
2 changes: 1 addition & 1 deletion src/devices/ros2Utils/Ros2Spinner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,4 +36,4 @@ void Ros2Spinner::threadRelease()
rclcpp::shutdown();
m_spun = false;
}
}
}
2 changes: 1 addition & 1 deletion src/devices/ros2Utils/Ros2Utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
class NodeCreator
{
public:
static rclcpp::Node::SharedPtr createNode(std::string name);
static rclcpp::Node::SharedPtr createNode(std::string name);
static rclcpp::Node::SharedPtr createNode(std::string name, rclcpp::NodeOptions& node_options);
};

Expand Down
12 changes: 12 additions & 0 deletions tests/misc/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
# SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium
# SPDX-License-Identifier: BSD-3-Clause

find_package(Perl QUIET)
if(PERL_FOUND AND NOT WIN32 AND IS_DIRECTORY "${CMAKE_SOURCE_DIR}/.git")
add_test(
NAME misc::check_style
COMMAND "${PERL_EXECUTABLE}" "${CMAKE_CURRENT_SOURCE_DIR}/check_style.pl"
WORKING_DIRECTORY "${CMAKE_SOURCE_DIR}"
)
endif()
Loading

0 comments on commit 813ab27

Please sign in to comment.