Skip to content

Commit

Permalink
Minor changes
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Tudela <[email protected]>
  • Loading branch information
ajtudela committed Apr 18, 2024
1 parent 01b0401 commit b4d74bf
Show file tree
Hide file tree
Showing 14 changed files with 104 additions and 98 deletions.
9 changes: 9 additions & 0 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -63,3 +63,12 @@ jobs:
flags: unittests
name: codecov-umbrella
slug: grupo-avispa/scitos2
- name: Upload cpp coverage to Coveralls
uses: coverallsapp/github-action@v2
with:
github-token: ${{ secrets.COVERALLS_REPO_TOKEN }}
fail-on-error: true
flag-name: unittests
debug: true
files: ros_ws/lcov/total_coverage.info,ros_ws/coveragepy/.coverage
format: lcov
9 changes: 6 additions & 3 deletions scitos2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "GNU" OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

option(COVERAGE_ENABLED "Enable code coverage" FALSE)

if(COVERAGE_ENABLED)
add_compile_options(--coverage)
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} --coverage")
Expand All @@ -51,7 +52,8 @@ endif()
# # Find ament macros and libraries
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(scitos2_msgs REQUIRED)
find_package(behaviortree_cpp_v3 REQUIRED)
find_package(nav2_behavior_tree REQUIRED)
Expand All @@ -67,7 +69,8 @@ include_directories(

set(dependencies
rclcpp
sensor_msgs
rclcpp_action
rclcpp_lifecycle
scitos2_msgs
behaviortree_cpp_v3
nav2_behavior_tree
Expand Down Expand Up @@ -112,7 +115,7 @@ install(DIRECTORY include/
)

install(DIRECTORY test/utils/
DESTINATION include/${PROJECT_NAME}/utils/
DESTINATION include/${PROJECT_NAME}/utils/
)

install(FILES scitos2_tree_nodes.xml DESTINATION share/${PROJECT_NAME})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,7 @@ class EmergencyStopService : public BtServiceNode<scitos2_msgs::srv::EmergencySt
* @param service_node_name Service name this node creates a client for
* @param conf BT node configuration
*/
EmergencyStopService(
const std::string & service_node_name,
const BT::NodeConfiguration & conf);

/**
* @brief Function to perform some user-defined operation on tick
*/
void on_tick() override;
EmergencyStopService(const std::string & service_node_name, const BT::NodeConfiguration & conf);
};

} // namespace scitos2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,7 @@ class ResetMotorStopService : public BtServiceNode<scitos2_msgs::srv::ResetMotor
* @param service_node_name Service name this node creates a client for
* @param conf BT node configuration
*/
ResetMotorStopService(
const std::string & service_node_name,
const BT::NodeConfiguration & conf);

/**
* @brief Function to perform some user-defined operation on tick
*/
void on_tick() override;
ResetMotorStopService(const std::string & service_node_name, const BT::NodeConfiguration & conf);
};

} // namespace scitos2_behavior_tree
Expand Down
3 changes: 2 additions & 1 deletion scitos2_behavior_tree/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@
<author email="[email protected]">Alberto Tudela</author>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>sensor_msgs</depend>
<depend>rclcpp_action</depend>
<depend>rclcpp_lifecycle</depend>
<depend>scitos2_msgs</depend>
<depend>behaviortree_cpp_v3</depend>
<depend>nav2_behavior_tree</depend>
Expand Down
9 changes: 1 addition & 8 deletions scitos2_behavior_tree/src/action/emergency_stop_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,21 +22,14 @@ namespace scitos2_behavior_tree
{

EmergencyStopService::EmergencyStopService(
const std::string & service_node_name,
const BT::NodeConfiguration & conf)
const std::string & service_node_name, const BT::NodeConfiguration & conf)
: BtServiceNode<scitos2_msgs::srv::EmergencyStop>(service_node_name, conf)
{
}

void EmergencyStopService::on_tick()
{
}

} // namespace scitos2_behavior_tree

#include "behaviortree_cpp_v3/bt_factory.h"
// LCOV_EXCL_START
BT_REGISTER_NODES(factory) {
factory.registerNodeType<scitos2_behavior_tree::EmergencyStopService>("EmergencyStop");
}
// LCOV_EXCL_STOP
Original file line number Diff line number Diff line change
Expand Up @@ -22,21 +22,14 @@ namespace scitos2_behavior_tree
{

ResetMotorStopService::ResetMotorStopService(
const std::string & service_node_name,
const BT::NodeConfiguration & conf)
const std::string & service_node_name, const BT::NodeConfiguration & conf)
: BtServiceNode<scitos2_msgs::srv::ResetMotorStop>(service_node_name, conf)
{
}

void ResetMotorStopService::on_tick()
{
}

} // namespace scitos2_behavior_tree

#include "behaviortree_cpp_v3/bt_factory.h"
// LCOV_EXCL_START
BT_REGISTER_NODES(factory) {
factory.registerNodeType<scitos2_behavior_tree::ResetMotorStopService>("ResetMotorStop");
}
// LCOV_EXCL_STOP
Original file line number Diff line number Diff line change
Expand Up @@ -21,17 +21,13 @@ namespace scitos2_behavior_tree
{

IsBumperActivatedCondition::IsBumperActivatedCondition(
const std::string & condition_name,
const BT::NodeConfiguration & conf)
: BT::ConditionNode(condition_name, conf),
bumper_topic_("/bumper"),
is_bumper_activated_(false)
const std::string & condition_name, const BT::NodeConfiguration & conf)
: BT::ConditionNode(condition_name, conf), bumper_topic_("/bumper"), is_bumper_activated_(false)
{
getInput("bumper_topic", bumper_topic_);
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
callback_group_ = node_->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive,
false);
rclcpp::CallbackGroupType::MutuallyExclusive, false);
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());

rclcpp::SubscriptionOptions sub_option;
Expand Down Expand Up @@ -60,8 +56,6 @@ void IsBumperActivatedCondition::bumperCallback(scitos2_msgs::msg::BumperStatus:
} // namespace scitos2_behavior_tree

#include "behaviortree_cpp_v3/bt_factory.h"
// LCOV_EXCL_START
BT_REGISTER_NODES(factory) {
factory.registerNodeType<scitos2_behavior_tree::IsBumperActivatedCondition>("IsBumperActivated");
}
// LCOV_EXCL_STOP
10 changes: 9 additions & 1 deletion scitos2_behavior_tree/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,12 @@
include_directories(.)

add_subdirectory(action)
add_subdirectory(condition)
add_subdirectory(condition)

# Test register
ament_add_gtest(test_register
test_register.cpp
)
ament_target_dependencies(test_register
${dependencies}
)
44 changes: 44 additions & 0 deletions scitos2_behavior_tree/test/test_register.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// Copyright (c) 2024 Alberto J. Tudela Roldán
// Copyright (c) 2024 Grupo Avispa, DTE, Universidad de Málaga
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>
#include "behaviortree_cpp_v3/bt_factory.h"
#include "behaviortree_cpp_v3/utils/shared_library.h"
#include "rclcpp/rclcpp.hpp"

TEST(Scitos2BehaviorTree, register_nodes)
{
BT::BehaviorTreeFactory factory;
BT::SharedLibrary loader;

factory.registerFromPlugin(loader.getOSName("scitos2_is_bumper_activated_condition_bt_node"));
factory.registerFromPlugin(loader.getOSName("scitos2_emergency_stop_service_bt_node"));
factory.registerFromPlugin(loader.getOSName("scitos2_reset_motor_stop_service_bt_node"));
}

int main(int argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);

// initialize ROS
rclcpp::init(argc, argv);

bool all_successful = RUN_ALL_TESTS();

// shutdown ROS
rclcpp::shutdown();

return all_successful;
}
24 changes: 9 additions & 15 deletions scitos2_modules/src/charger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,9 @@
namespace scitos2_modules
{

using std::placeholders::_1;
using std::placeholders::_2;

void Charger::configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name)
{
Expand All @@ -45,26 +48,21 @@ void Charger::configure(

// Create MIRA subscribers
authority_->subscribe<mira::robot::BatteryState>(
"/robot/charger/Battery", &Charger::batteryDataCallback, this);
"/robot/charger/Battery", std::bind(&Charger::batteryDataCallback, this, _1));
authority_->subscribe<uint8>(
"/robot/charger/ChargerStatus", &Charger::chargerStatusCallback, this);
"/robot/charger/ChargerStatus", std::bind(&Charger::chargerStatusCallback, this, _1));

// Create ROS services
save_persistent_errors_service_ = node->create_service<scitos2_msgs::srv::SavePersistentErrors>(
"charger/save_persistent_errors",
std::bind(
&Charger::savePersistentErrors, this,
std::placeholders::_1, std::placeholders::_2));
"charger/save_persistent_errors", std::bind(&Charger::savePersistentErrors, this, _1, _2));

RCLCPP_INFO(logger_, "Configured module : %s", plugin_name_.c_str());
}

void Charger::cleanup()
{
RCLCPP_INFO(
logger_,
"Cleaning up module : %s of type scitos2_module::Charger",
plugin_name_.c_str());
logger_, "Cleaning up module : %s of type scitos2_module::Charger", plugin_name_.c_str());
authority_.reset();
battery_pub_.reset();
charger_pub_.reset();
Expand All @@ -74,9 +72,7 @@ void Charger::cleanup()
void Charger::activate()
{
RCLCPP_INFO(
logger_,
"Activating module : %s of type scitos2_module::Charger",
plugin_name_.c_str());
logger_, "Activating module : %s of type scitos2_module::Charger", plugin_name_.c_str());
battery_pub_->on_activate();
charger_pub_->on_activate();
authority_->start();
Expand All @@ -85,9 +81,7 @@ void Charger::activate()
void Charger::deactivate()
{
RCLCPP_INFO(
logger_,
"Deactivating module : %s of type scitos2_module::Charger",
plugin_name_.c_str());
logger_, "Deactivating module : %s of type scitos2_module::Charger", plugin_name_.c_str());
authority_->checkout();
battery_pub_->on_deactivate();
charger_pub_->on_deactivate();
Expand Down
15 changes: 5 additions & 10 deletions scitos2_modules/src/display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,8 @@ void Display::configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,

// Create MIRA subscriber
authority_->subscribe<uint8>(
"/robot/StatusDisplayUserMenuEvent", &Display::menuDataCallback, this);
"/robot/StatusDisplayUserMenuEvent",
std::bind(&Display::menuDataCallback, this, std::placeholders::_1));

// Declare and read parameters
nav2_util::declare_parameter_if_not_declared(
Expand Down Expand Up @@ -99,29 +100,23 @@ void Display::configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
void Display::cleanup()
{
RCLCPP_INFO(
logger_,
"Cleaning up module : %s of type scitos2_module::Display",
plugin_name_.c_str());
logger_, "Cleaning up module : %s of type scitos2_module::Display", plugin_name_.c_str());
authority_.reset();
display_data_pub_.reset();
}

void Display::activate()
{
RCLCPP_INFO(
logger_,
"Activating module : %s of type scitos2_module::Display",
plugin_name_.c_str());
logger_, "Activating module : %s of type scitos2_module::Display", plugin_name_.c_str());
display_data_pub_->on_activate();
authority_->start();
}

void Display::deactivate()
{
RCLCPP_INFO(
logger_,
"Deactivating module : %s of type scitos2_module::Display",
plugin_name_.c_str());
logger_, "Deactivating module : %s of type scitos2_module::Display", plugin_name_.c_str());
authority_->checkout();
display_data_pub_->on_deactivate();
}
Expand Down
Loading

0 comments on commit b4d74bf

Please sign in to comment.