Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support multiple destinations with actions in nexus_transporter #69

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 0 additions & 17 deletions nexus_integration_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -63,22 +63,6 @@ rclcpp_components_register_node(mock_emergency_alarm_component
install(TARGETS mock_emergency_alarm_component RUNTIME DESTINATION lib/${PROJECT_NAME})

###############################################################################

add_library(mock_transporter SHARED src/mock_transporter.cpp)
target_include_directories(mock_transporter PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${pluginlub_INCLUDE_DIRS}
)
target_link_libraries(mock_transporter
PUBLIC
nexus_transporter::nexus_transporter
pluginlib::pluginlib
)

pluginlib_export_plugin_description_file(nexus_transporter mock_plugins.xml)

ament_export_libraries(mock_transporter)
ament_export_targets(export_${PROJECT_NAME})

###############################################################################
Expand Down Expand Up @@ -122,7 +106,6 @@ install(DIRECTORY ${zenoh_cfg_output_dir} DESTINATION share/${PROJECT_NAME}/conf

install(
TARGETS
mock_transporter
mock_printer
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
Expand Down
1 change: 1 addition & 0 deletions nexus_msgs/nexus_transporter_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)

set(msg_files
"msg/Destination.msg"
"msg/TransportationRequest.msg"
"msg/TransporterState.msg"
)
Expand Down
14 changes: 14 additions & 0 deletions nexus_msgs/nexus_transporter_msgs/msg/Destination.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
# Name of the destination
string name

# Action constants for the action field.
int32 ACTION_UNDEFINED=0
int32 ACTION_TRANSIT=1
int32 ACTION_PICKUP=2
int32 ACTION_DROPOFF=3

# The type of action to perform at the destination.
int32 action

# Additional parameters.
string params
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,5 @@ string requester
# from the previous request needs to move to the new destination.
string id

# The name of the destination
string destination

# The items that need to be transported to the destination.
# A json schema may be defined in the future for the contents of this field.
string payload
# The destinations for this itinerary.
Destination[] destinations
11 changes: 10 additions & 1 deletion nexus_system_orchestrator/src/bid_transporter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include "bid_transporter.hpp"

#include <nexus_transporter_msgs/msg/destination.hpp>

namespace nexus::system_orchestrator {

BT::PortsList BidTransporter::providedPorts()
Expand Down Expand Up @@ -50,7 +52,14 @@ BT::NodeStatus BidTransporter::onStart()
std::make_shared<endpoints::IsTransporterAvailableService::ServiceType::Request>();
req->request.id = this->_ctx->job_id;
req->request.requester = node->get_name();
req->request.destination = destination;
// TODO(Yadunund): Parse work order and assign action type and params.
// See https://github.com/osrf/nexus/issues/68.
req->request.destinations.emplace_back(
nexus_transporter_msgs::build<nexus_transporter_msgs::msg::Destination>()
.name(destination)
.action(nexus_transporter_msgs::msg::Destination::ACTION_PICKUP)
.params("")
);
// send request to all transporters in parallel
for (auto& [transporter_id, session] : this->_ctx->transporter_sessions)
{
Expand Down
10 changes: 9 additions & 1 deletion nexus_system_orchestrator/src/transporter_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "transporter_request.hpp"

#include <nexus_orchestrator_msgs/msg/workcell_task.hpp>
#include <nexus_transporter_msgs/msg/destination.hpp>

namespace nexus::system_orchestrator {

Expand Down Expand Up @@ -67,7 +68,14 @@ make_goal()
endpoints::TransportAction::ActionType::Goal goal;
goal.request.id = this->_ctx->job_id;
goal.request.requester = this->_node->get_name();
goal.request.destination = this->_destination;
// TODO(Yadunund): Parse work order and assign action type and params.
// See https://github.com/osrf/nexus/issues/68.
goal.request.destinations.emplace_back(
nexus_transporter_msgs::build<nexus_transporter_msgs::msg::Destination>()
.name(this->_destination)
.action(nexus_transporter_msgs::msg::Destination::ACTION_PICKUP)
.params("")
);
return goal;
}

Expand Down
26 changes: 25 additions & 1 deletion nexus_transporter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ set(dep_pkgs
rclcpp_lifecycle
rmf_utils
tf2_ros
yaml_cpp_vendor
yaml-cpp
)
foreach(pkg ${dep_pkgs})
find_package(${pkg} REQUIRED)
Expand All @@ -37,6 +39,7 @@ target_link_libraries(nexus_transporter
${rclcpp_action_TARGETS}
${rclcpp_lifecycle_TARGETS}
rmf_utils::rmf_utils
yaml-cpp::yaml-cpp
)

target_include_directories(nexus_transporter
Expand Down Expand Up @@ -68,6 +71,7 @@ target_link_libraries(nexus_transporter_component
${rclcpp_components_TARGETS}
${rclcpp_lifecycle_TARGETS}
${tf2_ros_TARGETS}
yaml-cpp::yaml-cpp
)

target_include_directories(nexus_transporter_component
Expand All @@ -89,7 +93,26 @@ target_compile_features(nexus_transporter_component INTERFACE cxx_std_17)
rclcpp_components_register_node(nexus_transporter_component
PLUGIN "nexus_transporter::TransporterNode"
EXECUTABLE nexus_transporter_node
EXECUTOR MultiThreadedExecutor)
EXECUTOR SingleThreadedExecutor)


#===============================================================================
# Mock transporter plugin.
add_library(mock_transporter SHARED src/transporters/mock_transporter.cpp)
target_include_directories(mock_transporter PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${pluginlub_INCLUDE_DIRS}
)
target_link_libraries(mock_transporter
PUBLIC
nexus_transporter
pluginlib::pluginlib
)

pluginlib_export_plugin_description_file(nexus_transporter src/transporters/plugins.xml)

ament_export_libraries(mock_transporter)

#===============================================================================
find_package(ament_cmake_uncrustify QUIET)
Expand Down Expand Up @@ -130,6 +153,7 @@ install(

install(
TARGETS
mock_transporter
nexus_transporter
nexus_transporter_component
EXPORT nexus_transporter
Expand Down
22 changes: 15 additions & 7 deletions nexus_transporter/include/nexus_transporter/Itinerary.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,21 @@
#ifndef NEXUS_TRANSPORTER__ITINERARY_HPP
#define NEXUS_TRANSPORTER__ITINERARY_HPP

#include <vector>

#include <nexus_transporter_msgs/msg/destination.hpp>

#include <rclcpp/rclcpp.hpp>

#include <rmf_utils/impl_ptr.hpp>

#include <yaml-cpp/yaml.h>

//==============================================================================
namespace nexus_transporter {

using Destination = nexus_transporter_msgs::msg::Destination;

/// An itinerary that is generated by the Transporter.
class Itinerary
{
Expand All @@ -34,8 +42,8 @@ class Itinerary
/// \param[in] id
/// A unique id for this itinerary
///
/// \param[in] destination
/// The destination for this itinerary
/// \param[in] destinations
/// The destinations for this itinerary
///
/// \param[in] transporter_name
/// The name of the transporter that is assigned to this itinerary
Expand All @@ -47,7 +55,7 @@ class Itinerary
/// The time until when this itinerary is valid
Itinerary(
std::string id,
std::string destination,
std::vector<Destination> destinations,
std::string transporter_name,
rclcpp::Time estimated_finish_time,
rclcpp::Time expiration_time
Expand All @@ -59,11 +67,11 @@ class Itinerary
/// Set the id
Itinerary& id(std::string id);

/// Get the destination
const std::string& destination() const;
/// Get the destinations
const std::vector<Destination>& destinations() const;

/// Set the destination
Itinerary& destination(std::string destination);
/// Set the destinations
Itinerary& destinations(std::vector<Destination> destination);

/// Get the name of the transporter
const std::string& transporter_name() const;
Expand Down
12 changes: 8 additions & 4 deletions nexus_transporter/include/nexus_transporter/Transporter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,11 @@
#ifndef NEXUS_TRANSPORTER__TRANSPORTER_HPP
#define NEXUS_TRANSPORTER__TRANSPORTER_HPP

#include <vector>

#include <rclcpp_lifecycle/lifecycle_node.hpp>

#include <nexus_transporter_msgs/msg/destination.hpp>
#include <nexus_transporter_msgs/msg/transporter_state.hpp>

#include <nexus_transporter/Itinerary.hpp>
Expand All @@ -39,6 +42,7 @@ class Transporter
using TransportFeedback = std::function<void(const TransporterState& state)>;
/// A callback to execute once the transportation is completed
using TransportCompleted = std::function<void(bool success)>;
/// Destination.

/// Configure the transporter including getting relevant information from
/// ROS 2 parameters. (Eg. List of destinations)
Expand All @@ -59,13 +63,13 @@ class Transporter
/// \param[in] job_id
/// An id for this request.
///
/// \param[in] destination
/// The name of the destination
/// \return A nullopt is returned if the destination is not valid.
/// \param[in] destinations
/// A list of destinations.
/// \return A nullopt is returned if the destinations is not valid.
// TODO(YV): Consider creating a separate class for destination
virtual std::optional<Itinerary> get_itinerary(
const std::string& job_id,
const std::string& destination) = 0;
const std::vector<Destination>& destinations) = 0;

/// Request the transporter to go to a destination. This call should be
/// non-blocking.
Expand Down
3 changes: 3 additions & 0 deletions nexus_transporter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@
<depend>rclcpp_lifecycle</depend>
<depend>rmf_utils</depend>
<depend>tf2_ros</depend>
<depend>yaml-cpp</depend>
<depend>yaml_cpp_vendor</depend>


<test_depend>ament_cmake_catch2</test_depend>
<test_depend>ament_cmake_uncrustify</test_depend>
Expand Down
Loading
Loading