Skip to content

Commit

Permalink
Sync 6.5 to main (#37)
Browse files Browse the repository at this point in the history
  • Loading branch information
MikeWrock authored Dec 5, 2024
1 parent b163653 commit a657adf
Show file tree
Hide file tree
Showing 77 changed files with 408 additions and 195 deletions.
25 changes: 12 additions & 13 deletions src/example_behaviors/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,19 +20,18 @@ find_package(moveit_pro_ml REQUIRED)
add_library(
example_behaviors
SHARED
src/add_two_ints_service_client.cpp
src/convert_mtc_solution_to_joint_trajectory.cpp
src/delayed_message.cpp
src/fibonacci_action_client.cpp
src/get_string_from_topic.cpp
src/hello_world.cpp
src/ndt_registration.cpp
src/publish_color_rgba.cpp
src/ransac_registration.cpp
src/sam2_segmentation.cpp
src/setup_mtc_pick_from_pose.cpp
src/setup_mtc_place_from_pose.cpp
src/setup_mtc_wave_hand.cpp
src/example_add_two_ints_service_client.cpp
src/example_convert_mtc_solution_to_joint_trajectory.cpp
src/example_delayed_message.cpp
src/example_get_string_from_topic.cpp
src/example_fibonacci_action_client.cpp
src/example_hello_world.cpp
src/example_publish_color_rgba.cpp
src/example_setup_mtc_pick_from_pose.cpp
src/example_setup_mtc_place_from_pose.cpp
src/example_setup_mtc_wave_hand.cpp
src/example_ndt_registration.cpp
src/example_ransac_registration.cpp
src/register_behaviors.cpp)
target_include_directories(
example_behaviors
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,10 @@ using AddTwoInts = example_interfaces::srv::AddTwoInts;

namespace example_behaviors
{
class AddTwoIntsServiceClient final : public ServiceClientBehaviorBase<AddTwoInts>
class ExampleAddTwoIntsServiceClient final : public ServiceClientBehaviorBase<AddTwoInts>
{
public:
AddTwoIntsServiceClient(const std::string& name, const BT::NodeConfiguration& config,
ExampleAddTwoIntsServiceClient(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<BehaviorContext>& shared_resources);

/** @brief Implementation of the required providedPorts() function for the hello_world Behavior. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,10 @@ namespace example_behaviors
* | sampling_rate | Input | int |
* | joint_trajectory | Output | trajectory_msgs::msg::JointTrajectory |
*/
class ConvertMtcSolutionToJointTrajectory final : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
class ExampleConvertMtcSolutionToJointTrajectory final : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
{
public:
ConvertMtcSolutionToJointTrajectory(const std::string& name, const BT::NodeConfiguration& config,
ExampleConvertMtcSolutionToJointTrajectory(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

static BT::PortsList providedPorts();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
namespace example_behaviors
{
/**
* @brief DelayedMessage will use FailureLoggerROS to log a "Hello World" message after the duration specified on the input port
* @brief ExampleDelayedMessage will use FailureLoggerROS to log a "Hello World" message after the duration specified on the input port
*/
class DelayedMessage : public moveit_studio::behaviors::SharedResourcesNode<BT::StatefulActionNode>
class ExampleDelayedMessage : public moveit_studio::behaviors::SharedResourcesNode<BT::StatefulActionNode>
{
private:
std::chrono::time_point<std::chrono::steady_clock> start_time_;
Expand All @@ -33,7 +33,7 @@ class DelayedMessage : public moveit_studio::behaviors::SharedResourcesNode<BT::
* @details An important limitation is that the members of the base Behavior class are not instantiated until after
* the initialize() function is called, so these classes should not be used within the constructor.
*/
DelayedMessage(const std::string& name, const BT::NodeConfiguration& config,
ExampleDelayedMessage(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,10 @@ using Fibonacci = example_interfaces::action::Fibonacci;

namespace example_behaviors
{
class FibonacciActionClient final : public ActionClientBehaviorBase<Fibonacci>
class ExampleFibonacciActionClient final : public ActionClientBehaviorBase<Fibonacci>
{
public:
FibonacciActionClient(const std::string& name, const BT::NodeConfiguration& config,
ExampleFibonacciActionClient(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<BehaviorContext>& shared_resources);

/** @brief Implementation of the required providedPorts() function for the hello_world Behavior. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,10 @@ using moveit_studio::behaviors::GetMessageFromTopicBehaviorBase;

namespace example_behaviors
{
class GetStringFromTopic final : public GetMessageFromTopicBehaviorBase<std_msgs::msg::String>
class ExampleGetStringFromTopic final : public GetMessageFromTopicBehaviorBase<std_msgs::msg::String>
{
public:
GetStringFromTopic(const std::string& name, const BT::NodeConfiguration& config,
ExampleGetStringFromTopic(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<BehaviorContext>& shared_resources);

/** @brief Implementation of the required providedPorts() function for the hello_world Behavior. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,9 @@
namespace example_behaviors
{
/**
* @brief The HelloWorld Behavior uses FailureLoggerROS to log a "Hello World" message and will always return SUCCESS
* @brief The ExampleHelloWorld Behavior uses FailureLoggerROS to log a "Hello World" message and will always return SUCCESS
*/
class HelloWorld : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
class ExampleHelloWorld : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
{
public:
/**
Expand All @@ -25,7 +25,7 @@ class HelloWorld : public moveit_studio::behaviors::SharedResourcesNode<BT::Sync
* @details An important limitation is that the members of the base Behavior class are not instantiated until after
* the initialize() function is called, so these classes should not be used within the constructor.
*/
HelloWorld(const std::string& name, const BT::NodeConfiguration& config,
ExampleHelloWorld(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

/**
Expand All @@ -46,9 +46,9 @@ class HelloWorld : public moveit_studio::behaviors::SharedResourcesNode<BT::Sync
static BT::KeyValueVector metadata();

/**
* @brief Implementation of BT::SyncActionNode::tick() for HelloWorld.
* @brief Implementation of BT::SyncActionNode::tick() for ExampleHelloWorld.
* @details This function is where the Behavior performs its work when the behavior tree is being run.
* Since HelloWorld is derived from BT::SyncActionNode, it is very important that its tick() function always finishes
* Since ExampleHelloWorld is derived from BT::SyncActionNode, it is very important that its tick() function always finishes
* very quickly. If tick() blocks before returning, it will block execution of the entire behavior tree, which may
* have undesirable consequences for other Behaviors that require a fast update rate to work correctly.
* @return BT::NodeStatus::RUNNING, BT::NodeStatus::SUCCESS, or BT::NodeStatus::FAILURE depending on the result of the
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace example_behaviors
/**
* @brief TODO(...)
*/
class NDTRegistration : public moveit_studio::behaviors::AsyncBehaviorBase
class ExampleNDTRegistration : public moveit_studio::behaviors::AsyncBehaviorBase
{
public:
/**
Expand All @@ -22,7 +22,7 @@ class NDTRegistration : public moveit_studio::behaviors::AsyncBehaviorBase
* @param config This contains runtime configuration info for this Behavior, such as the mapping between the Behavior's data ports on the behavior tree's blackboard. This will be set by the behavior tree factory when this Behavior is created within a new behavior tree.
* @details An important limitation is that the members of the base Behavior class are not instantiated until after the initialize() function is called, so these classes should not be used within the constructor.
*/
NDTRegistration(const std::string& name, const BT::NodeConfiguration& config, const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);
ExampleNDTRegistration(const std::string& name, const BT::NodeConfiguration& config, const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

/**
* @brief Implementation of the required providedPorts() function for the Behavior.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@

namespace example_behaviors
{
class PublishColorRGBA final : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
class ExamplePublishColorRGBA final : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
{
public:
PublishColorRGBA(const std::string& name, const BT::NodeConfiguration& config,
ExamplePublishColorRGBA(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

static BT::PortsList providedPorts();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace example_behaviors
/**
* @brief TODO(...)
*/
class RANSACRegistration : public moveit_studio::behaviors::AsyncBehaviorBase
class ExampleRANSACRegistration : public moveit_studio::behaviors::AsyncBehaviorBase
{
public:
/**
Expand All @@ -22,7 +22,7 @@ class RANSACRegistration : public moveit_studio::behaviors::AsyncBehaviorBase
* @param config This contains runtime configuration info for this Behavior, such as the mapping between the Behavior's data ports on the behavior tree's blackboard. This will be set by the behavior tree factory when this Behavior is created within a new behavior tree.
* @details An important limitation is that the members of the base Behavior class are not instantiated until after the initialize() function is called, so these classes should not be used within the constructor.
*/
RANSACRegistration(const std::string& name, const BT::NodeConfiguration& config, const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);
ExampleRANSACRegistration(const std::string& name, const BT::NodeConfiguration& config, const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

/**
* @brief Implementation of the required providedPorts() function for the Behavior.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@ namespace example_behaviors
* | task | Bidirectional | std::shared_ptr<moveit::task_constructor::Task> |
* | grasp_pose | Input | geometry_msgs::msg::PoseStamped |
*/
class SetupMtcPickFromPose final : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
class ExampleSetupMtcPickFromPose final : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
{
public:
SetupMtcPickFromPose(const std::string& name, const BT::NodeConfiguration& config,
ExampleSetupMtcPickFromPose(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

static BT::PortsList providedPorts();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@ namespace example_behaviors
* | task | Bidirectional | std::shared_ptr<moveit::task_constructor::Task> |
* | grasp_pose | Input | geometry_msgs::msg::PoseStamped |
*/
class SetupMtcPlaceFromPose final : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
class ExampleSetupMtcPlaceFromPose final : public moveit_studio::behaviors::SharedResourcesNode<BT::SyncActionNode>
{
public:
SetupMtcPlaceFromPose(const std::string& name, const BT::NodeConfiguration& config,
ExampleSetupMtcPlaceFromPose(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

static BT::PortsList providedPorts();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
namespace example_behaviors
{
/**
* @brief The SetupMTCWaveHand behavior makes any robot move the end of its arm back and forth.
* @brief The ExampleSetupMTCWaveHand behavior makes any robot move the end of its arm back and forth.
* @details This is an example of a behavior that uses MoveIt Task Constructor to configure an MTC task,
* which can be planned and executed by MoveIt Pro's core PlanMTCTask and ExecuteMTCTask Behaviors.
* It is derived from AsyncBehaviorBase, an extension of the templated SharedResourcesNode type,
Expand All @@ -24,11 +24,11 @@ namespace example_behaviors
* if the process completed successfully or was canceled,
* or an error message if the process failed unexpectedly.
*/
class SetupMTCWaveHand final : public moveit_studio::behaviors::AsyncBehaviorBase
class ExampleSetupMTCWaveHand final : public moveit_studio::behaviors::AsyncBehaviorBase
{
public:
/**
* @brief Constructor for the SetupMTCWaveHand behavior.
* @brief Constructor for the ExampleSetupMTCWaveHand behavior.
* @param name The name of a particular instance of this Behavior. This will be set by the behavior
* tree factory when this Behavior is created within a new behavior tree.
* @param shared_resources A shared_ptr to a BehaviorContext that is shared among all
Expand All @@ -38,17 +38,17 @@ class SetupMTCWaveHand final : public moveit_studio::behaviors::AsyncBehaviorBas
* between the Behavior's data ports on the behavior tree's blackboard. This will be set by the
* behavior tree factory when this Behavior is created within a new behavior tree.
*/
SetupMTCWaveHand(const std::string& name, const BT::NodeConfiguration& config,
ExampleSetupMTCWaveHand(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

/**
* @brief Implementation of the required providedPorts() function for the SetupMTCWaveHand Behavior.
* @brief Implementation of the required providedPorts() function for the ExampleSetupMTCWaveHand Behavior.
* @details The BehaviorTree.CPP library requires that Behaviors must implement a static function
* named providedPorts() which defines their input and output ports. If the Behavior does not use
* any ports, this function must return an empty BT::PortsList.
* This function returns a list of ports with their names and port info, which is used internally
* by the behavior tree.
* @return SetupMTCWaveHand has one data port: a bidirectional port named "task", which is a shared_ptr
* @return ExampleSetupMTCWaveHand has one data port: a bidirectional port named "task", which is a shared_ptr
* to an MTC task object. This function returns a BT::PortsList that declares this single port.
*/
static BT::PortsList providedPorts();
Expand All @@ -62,7 +62,7 @@ class SetupMTCWaveHand final : public moveit_studio::behaviors::AsyncBehaviorBas

private:
/**
* @brief Async thread for SetupMTCWaveHand. Adds MTC stages to an MTC task provided on a data port.
* @brief Async thread for ExampleSetupMTCWaveHand. Adds MTC stages to an MTC task provided on a data port.
* @details This function is where the Behavior performs its work asynchronously while the behavior tree ticks.
* It is very important that behaviors return from being ticked very quickly because if it blocks before returning
* it will block execution of the entire behavior tree, which may have undesirable consequences for other Behaviors
Expand Down
Original file line number Diff line number Diff line change
@@ -1,17 +1,17 @@
#include <example_behaviors/add_two_ints_service_client.hpp>
#include <example_behaviors/example_add_two_ints_service_client.hpp>

// Include the template implementation for GetMessageFromTopicBehaviorBase<T>.
#include <moveit_studio_behavior_interface/impl/service_client_behavior_base_impl.hpp>
namespace example_behaviors
{
AddTwoIntsServiceClient::AddTwoIntsServiceClient(
ExampleAddTwoIntsServiceClient::ExampleAddTwoIntsServiceClient(
const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources)
: ServiceClientBehaviorBase<example_interfaces::srv::AddTwoInts>(name, config, shared_resources)
{
}

BT::PortsList AddTwoIntsServiceClient::providedPorts()
BT::PortsList ExampleAddTwoIntsServiceClient::providedPorts()
{
// This node has three input ports and one output port
return BT::PortsList({
Expand All @@ -22,13 +22,13 @@ BT::PortsList AddTwoIntsServiceClient::providedPorts()
});
}

BT::KeyValueVector AddTwoIntsServiceClient::metadata()
BT::KeyValueVector ExampleAddTwoIntsServiceClient::metadata()
{
return { { "subcategory", "Example" },
return { { "subcategory", "Example Behaviors" },
{ "description", "Calls a service to add two integers and makes the result available on an output port." } };
}

tl::expected<std::string, std::string> AddTwoIntsServiceClient::getServiceName()
tl::expected<std::string, std::string> ExampleAddTwoIntsServiceClient::getServiceName()
{
const auto service_name = getInput<std::string>("service_name");
if (const auto error = moveit_studio::behaviors::maybe_error(service_name))
Expand All @@ -38,7 +38,7 @@ tl::expected<std::string, std::string> AddTwoIntsServiceClient::getServiceName()
return service_name.value();
}

tl::expected<AddTwoInts::Request, std::string> AddTwoIntsServiceClient::createRequest()
tl::expected<AddTwoInts::Request, std::string> ExampleAddTwoIntsServiceClient::createRequest()
{
const auto a = getInput<int>("addend1");
const auto b = getInput<int>("addend2");
Expand All @@ -49,7 +49,7 @@ tl::expected<AddTwoInts::Request, std::string> AddTwoIntsServiceClient::createRe
return example_interfaces::build<AddTwoInts::Request>().a(a.value()).b(b.value());
}

tl::expected<bool, std::string> AddTwoIntsServiceClient::processResponse(const AddTwoInts::Response& response)
tl::expected<bool, std::string> ExampleAddTwoIntsServiceClient::processResponse(const AddTwoInts::Response& response)
{
setOutput<int>("result", response.sum);
return { true };
Expand Down
Loading

0 comments on commit a657adf

Please sign in to comment.