Skip to content

Commit

Permalink
Merge pull request #21 from threeal/19-add-navigation-consumer
Browse files Browse the repository at this point in the history
19 add navigation consumer
  • Loading branch information
threeal authored Apr 26, 2021
2 parents 573cdaa + d1fed37 commit cbd6e50
Show file tree
Hide file tree
Showing 8 changed files with 351 additions and 23 deletions.
3 changes: 2 additions & 1 deletion .github/workflows/build-and-test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ jobs:
- name: Checking out
uses: actions/checkout@v2.3.4
- name: Building and testing
uses: ichiro-its/ros2-ci@v0.4.1
uses: ichiro-its/ros2-ci@v1.0.0
with:
ros2-distro: foxy
external-repos: ichiro-its/keisan#v0.2.0
15 changes: 14 additions & 1 deletion tosshin_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,30 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(keisan REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tosshin_interfaces REQUIRED)

install(DIRECTORY "include" DESTINATION ".")

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_lint_auto REQUIRED)

ament_add_gtest(${PROJECT_NAME}_tests
"test/utility_test.cpp")

target_include_directories(${PROJECT_NAME}_tests PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)

ament_target_dependencies(${PROJECT_NAME}_tests
keisan rclcpp tosshin_interfaces)

ament_lint_auto_find_test_dependencies()
endif()

ament_export_dependencies(rclcpp tosshin_interfaces)
ament_export_dependencies(keisan rclcpp tosshin_interfaces)
ament_export_include_directories("include")

ament_package()
212 changes: 212 additions & 0 deletions tosshin_cpp/include/tosshin_cpp/navigation/navigation_consumer.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,212 @@
// Copyright (c) 2021 Alfi Maulana
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
// THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
// THE SOFTWARE.

#ifndef TOSSHIN_CPP__NAVIGATION__NAVIGATION_CONSUMER_HPP_
#define TOSSHIN_CPP__NAVIGATION__NAVIGATION_CONSUMER_HPP_

#include <rclcpp/rclcpp.hpp>
#include <tosshin_interfaces/tosshin_interfaces.hpp>

#include <memory>

namespace tosshin_cpp
{

using Maneuver = tosshin_interfaces::msg::Maneuver;
using Odometry = tosshin_interfaces::msg::Odometry;
using ConfigureManeuver = tosshin_interfaces::srv::ConfigureManeuver;

class NavigationConsumer
{
public:
inline NavigationConsumer();
inline explicit NavigationConsumer(rclcpp::Node::SharedPtr node);

inline void set_node(rclcpp::Node::SharedPtr node);

inline const Maneuver & configure_maneuver(const Maneuver & maneuver);
inline const Maneuver & configure_maneuver_to_stop();

inline void set_maneuver(const Maneuver & maneuver);

inline rclcpp::Node::SharedPtr get_node();

inline const Odometry & get_odometry();
inline const Maneuver & get_maneuver();

private:
rclcpp::Node::SharedPtr node;

rclcpp::Subscription<Odometry>::SharedPtr odometry_subscription;

rclcpp::Subscription<Maneuver>::SharedPtr maneuver_event_subscription;
rclcpp::Publisher<Maneuver>::SharedPtr maneuver_input_publisher;

rclcpp::Client<ConfigureManeuver>::SharedPtr configure_maneuver_client;

Odometry current_odometry;
Maneuver current_maneuver;
};

NavigationConsumer::NavigationConsumer()
{
}

NavigationConsumer::NavigationConsumer(rclcpp::Node::SharedPtr node)
{
set_node(node);
}

void NavigationConsumer::set_node(rclcpp::Node::SharedPtr node)
{
// Initialize the node
{
this->node = node;

RCLCPP_INFO_STREAM(
get_node()->get_logger(),
"Node initialized on " << get_node()->get_name() << "!");
}

// Initialize the odometry subscription
{
odometry_subscription = get_node()->create_subscription<Odometry>(
"navigation/odometry", 10,
[this](const Odometry::SharedPtr msg) {
current_odometry = *msg;
});

RCLCPP_INFO_STREAM(
get_node()->get_logger(),
"Odometry subscription initialized on " <<
odometry_subscription->get_topic_name() << "!");
}

// Initialize the maneuver event subscription
{
maneuver_event_subscription = get_node()->create_subscription<Maneuver>(
"/navigation/maneuver_event", 10,
[this](const Maneuver::SharedPtr msg) {
current_maneuver = *msg;
});

RCLCPP_INFO_STREAM(
get_node()->get_logger(),
"Maneuver event subscription initialized on " <<
maneuver_event_subscription->get_topic_name() << "!");
}

// Initialize the maneuver input publisher
{
maneuver_input_publisher = get_node()->create_publisher<Maneuver>(
"/navigation/maneuver_input", 10);

RCLCPP_INFO_STREAM(
get_node()->get_logger(),
"Maneuver input publisher initialized on " <<
maneuver_input_publisher->get_topic_name() << "!");
}

// Initialize the configure maneuver client
{
configure_maneuver_client = get_node()->create_client<ConfigureManeuver>(
"/navigation/configure_maneuver");

RCLCPP_INFO_STREAM(
get_node()->get_logger(),
"Configure maneuver client initialized on " <<
configure_maneuver_client->get_service_name() << "!");

// Request maneuver data
{
if (configure_maneuver_client->wait_for_service(std::chrono::seconds(1))) {
auto request = std::make_shared<ConfigureManeuver::Request>();

configure_maneuver_client->async_send_request(
request, [this](rclcpp::Client<ConfigureManeuver>::SharedFuture future) {
auto response = future.get();
if (response->maneuver.size() > 0) {
current_maneuver = response->maneuver.front();
}
});
} else {
}
}
}
}

const Maneuver & NavigationConsumer::configure_maneuver(const Maneuver & maneuver)
{
if (!configure_maneuver_client->wait_for_service(std::chrono::seconds(1))) {
throw std::runtime_error("configure maneuver service is not ready");
}

auto request = std::make_shared<ConfigureManeuver::Request>();
request->maneuver.push_back(maneuver);

auto future = configure_maneuver_client->async_send_request(request);
if (rclcpp::spin_until_future_complete(get_node(), future) != rclcpp::FutureReturnCode::SUCCESS) {
throw std::runtime_error("failed to call configure maneuver service");
}

auto response = future.get();
if (response->maneuver.size() < 1) {
throw std::runtime_error("maneuver not configured");
}

current_maneuver = response->maneuver.front();

return current_maneuver;
}

const Maneuver & NavigationConsumer::configure_maneuver_to_stop()
{
Maneuver maneuver;

maneuver.forward = 0.0;
maneuver.left = 0.0;
maneuver.yaw = 0.0;

return configure_maneuver(maneuver);
}

void NavigationConsumer::set_maneuver(const Maneuver & maneuver)
{
maneuver_input_publisher->publish(maneuver);
}

rclcpp::Node::SharedPtr NavigationConsumer::get_node()
{
return node;
}

const Odometry & NavigationConsumer::get_odometry()
{
return current_odometry;
}

const Maneuver & NavigationConsumer::get_maneuver()
{
return current_maneuver;
}

} // namespace tosshin_cpp

#endif // TOSSHIN_CPP__NAVIGATION__NAVIGATION_CONSUMER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,13 @@
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
// THE SOFTWARE.

#ifndef TOSSHIN_CPP__NAVIGATION_PROVIDER_HPP_
#define TOSSHIN_CPP__NAVIGATION_PROVIDER_HPP_
#ifndef TOSSHIN_CPP__NAVIGATION__NAVIGATION_PROVIDER_HPP_
#define TOSSHIN_CPP__NAVIGATION__NAVIGATION_PROVIDER_HPP_

#include <rclcpp/rclcpp.hpp>
#include <tosshin_interfaces/tosshin_interfaces.hpp>

#include <memory>
#include <string>

namespace tosshin_cpp
{
Expand All @@ -37,19 +36,20 @@ using ConfigureManeuver = tosshin_interfaces::srv::ConfigureManeuver;
class NavigationProvider
{
public:
NavigationProvider();
explicit NavigationProvider(rclcpp::Node::SharedPtr node);
inline NavigationProvider();
inline explicit NavigationProvider(rclcpp::Node::SharedPtr node);

protected:
virtual const Maneuver & configure_maneuver(const Maneuver & maneuver);
inline void set_node(rclcpp::Node::SharedPtr node);

inline void set_odometry(const Odometry & odometry);
inline void set_maneuver(const Maneuver & maneuver);

void set_node(rclcpp::Node::SharedPtr node);
inline rclcpp::Node::SharedPtr get_node();

void set_odometry(const Odometry & odometry);
void set_maneuver(const Maneuver & maneuver);
inline const Maneuver & get_maneuver();

rclcpp::Node::SharedPtr get_node();
const Maneuver & get_maneuver();
protected:
inline virtual const Maneuver & on_configure_maneuver(const Maneuver & maneuver);

private:
rclcpp::Node::SharedPtr node;
Expand All @@ -73,11 +73,6 @@ NavigationProvider::NavigationProvider(rclcpp::Node::SharedPtr node)
set_node(node);
}

const Maneuver & NavigationProvider::configure_maneuver(const Maneuver & maneuver)
{
return maneuver;
}

void NavigationProvider::set_node(rclcpp::Node::SharedPtr node)
{
// Initialize the node
Expand Down Expand Up @@ -157,8 +152,8 @@ void NavigationProvider::set_odometry(const Odometry & odometry)

void NavigationProvider::set_maneuver(const Maneuver & maneuver)
{
current_maneuver = configure_maneuver(maneuver);
// maneuver_event_publisher->publish(current_maneuver);
current_maneuver = on_configure_maneuver(maneuver);
maneuver_event_publisher->publish(current_maneuver);
}

rclcpp::Node::SharedPtr NavigationProvider::get_node()
Expand All @@ -171,6 +166,11 @@ const Maneuver & NavigationProvider::get_maneuver()
return current_maneuver;
}

const Maneuver & NavigationProvider::on_configure_maneuver(const Maneuver & maneuver)
{
return maneuver;
}

} // namespace tosshin_cpp

#endif // TOSSHIN_CPP__NAVIGATION_PROVIDER_HPP_
#endif // TOSSHIN_CPP__NAVIGATION__NAVIGATION_PROVIDER_HPP_
5 changes: 4 additions & 1 deletion tosshin_cpp/include/tosshin_cpp/tosshin_cpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,9 @@
#ifndef TOSSHIN_CPP__TOSSHIN_CPP_HPP_
#define TOSSHIN_CPP__TOSSHIN_CPP_HPP_

#include "./navigation_provider.hpp"
#include "./navigation/navigation_consumer.hpp"
#include "./navigation/navigation_provider.hpp"

#include "./utility.hpp"

#endif // TOSSHIN_CPP__TOSSHIN_CPP_HPP_
Loading

0 comments on commit cbd6e50

Please sign in to comment.