Skip to content
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
3 changes: 2 additions & 1 deletion src/example_behaviors/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ find_package(moveit_studio_common REQUIRED)
find_package(example_interfaces REQUIRED)
moveit_studio_package()

set(THIS_PACKAGE_INCLUDE_DEPENDS cartesian_planning moveit_studio_behavior
set(THIS_PACKAGE_INCLUDE_DEPENDS cartesian_planning geometry_msgs moveit_studio_behavior
moveit_studio_behavior_interface pluginlib moveit_studio_vision
moveit_studio_vision_msgs PCL pcl_conversions pcl_ros example_interfaces)
foreach(package IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
Expand All @@ -18,6 +18,7 @@ add_library(
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_pose_stamped_from_topic.cpp
src/example_get_string_from_topic.cpp
src/example_fibonacci_action_client.cpp
src/example_hello_world.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
#pragma once

#include <moveit_studio_behavior_interface/get_message_from_topic.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>

namespace example_behaviors
{
class ExampleGetPoseStampedFromTopic final
: public moveit_studio::behaviors::GetMessageFromTopicBehaviorBase<geometry_msgs::msg::PoseStamped>
{
public:
ExampleGetPoseStampedFromTopic(const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources);

static BT::PortsList providedPorts();

static BT::KeyValueVector metadata();

private:
std::shared_future<tl::expected<bool, std::string>>& getFuture() override
{
return future_;
}

std::shared_future<tl::expected<bool, std::string>> future_;
};
} // namespace example_behaviors
1 change: 1 addition & 0 deletions src/example_behaviors/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

<depend>moveit_studio_behavior_interface</depend>
<depend>example_interfaces</depend>
<depend>geometry_msgs</depend>
<depend>perception_pcl</depend>
<depend>moveit_ros_planning_interface</depend>
<depend>moveit_studio_vision_msgs</depend>
Expand Down
34 changes: 34 additions & 0 deletions src/example_behaviors/src/example_get_pose_stamped_from_topic.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
#include <example_behaviors/example_get_pose_stamped_from_topic.hpp>

#include <moveit_studio_behavior_interface/impl/get_message_from_topic_impl.hpp>

namespace example_behaviors
{
// Mirrors the PoseStamped specialization produced by generate_topic_interface_behaviors.py so developers
// can see the generated pattern inside example_behaviors.
ExampleGetPoseStampedFromTopic::ExampleGetPoseStampedFromTopic(
const std::string& name, const BT::NodeConfiguration& config,
const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources)
: GetMessageFromTopicBehaviorBase<geometry_msgs::msg::PoseStamped>(name, config, shared_resources)
{
}

BT::PortsList ExampleGetPoseStampedFromTopic::providedPorts()
{
return BT::PortsList({
BT::InputPort<std::string>(kPortIDTopicName, "/pose_stamped",
"Topic that publishes <code>geometry_msgs::msg::PoseStamped</code> messages."),
BT::OutputPort<geometry_msgs::msg::PoseStamped>(kPortIDMessageOut, "{pose_stamped}",
"Output pose from the subscribed topic."),
});
}

BT::KeyValueVector ExampleGetPoseStampedFromTopic::metadata()
{
return { { "subcategory", "Example Behaviors" },
{ "description", "Capture a pose stamped message from a topic and store it on the blackboard." } };
}

} // namespace example_behaviors

template class moveit_studio::behaviors::GetMessageFromTopicBehaviorBase<geometry_msgs::msg::PoseStamped>;
4 changes: 4 additions & 0 deletions src/example_behaviors/src/register_behaviors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include <example_behaviors/example_create_string_msg.hpp>
#include <example_behaviors/example_delayed_message.hpp>
#include <example_behaviors/example_fibonacci_action_client.hpp>
#include <example_behaviors/example_get_pose_stamped_from_topic.hpp>
#include <example_behaviors/example_get_string_from_topic.hpp>
#include <example_behaviors/example_hello_world.hpp>
#include <example_behaviors/example_ndt_registration.hpp>
Expand Down Expand Up @@ -36,6 +37,9 @@ class ExampleBehaviorsLoader : public moveit_studio::behaviors::SharedResourcesN
shared_resources);
moveit_studio::behaviors::registerBehavior<ExampleGetStringFromTopic>(factory, "ExampleGetStringFromTopic",
shared_resources);
moveit_studio::behaviors::registerBehavior<ExampleGetPoseStampedFromTopic>(factory,
"ExampleGetPoseStampedFromTopic",
shared_resources);
moveit_studio::behaviors::registerBehavior<ExampleAddTwoIntsServiceClient>(
factory, "ExampleAddTwoIntsServiceClient", shared_resources);
moveit_studio::behaviors::registerBehavior<ExampleFibonacciActionClient>(factory, "ExampleFibonacciActionClient",
Expand Down
1 change: 1 addition & 0 deletions src/factory_sim/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,7 @@ objectives:
# Add additional plugin loaders as needed.
core:
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
- "moveit_studio::behaviors::CoreBehaviorsLoader"
- "moveit_studio::behaviors::MTCCoreBehaviorsLoader"
- "moveit_studio::behaviors::ServoBehaviorsLoader"
Expand Down
1 change: 1 addition & 0 deletions src/grinding_sim/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
Expand Down
1 change: 1 addition & 0 deletions src/hangar_sim/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
Expand Down
1 change: 1 addition & 0 deletions src/lab_sim/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
- "moveit_studio::behaviors::MujocoBehaviorsLoader"
# Specify source folder for objectives
# [Required]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
objective_library_paths:
core_objectives:
package_name: "moveit_pro_objectives"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,6 +155,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
- "moveit_studio::behaviors::MujocoBehaviorsLoader"
# Specify source folder for objectives
# [Required]
Expand Down
1 change: 1 addition & 0 deletions src/moveit_pro_ur_configs/multi_arm_sim/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -165,6 +165,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,6 +172,7 @@ objectives:
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
- "moveit_studio::behaviors::TopicInterfaceBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
Expand Down
Loading