Add last dangling changes before humble merge
This commit is contained in:
@@ -8,6 +8,9 @@
|
||||
#define AnimationGoalPtr const std::shared_ptr<const ign_actor_plugin::action::Animation::Goal>
|
||||
#define AnimationServerGoalPtr const std::shared_ptr<rclcpp_action::ServerGoalHandle<ign_actor_plugin::action::Animation>>&
|
||||
|
||||
#define MovementGoalPtr const std::shared_ptr<const ign_actor_plugin::action::Movement::Goal>
|
||||
#define MovementServerGoalPtr const std::shared_ptr<rclcpp_action::ServerGoalHandle<ign_actor_plugin::action::Movement>>&
|
||||
|
||||
IGNITION_ADD_PLUGIN(
|
||||
ActorSystem,
|
||||
ignition::gazebo::System,
|
||||
@@ -41,8 +44,6 @@ void ActorSystem::Configure(const ignition::gazebo::Entity &_entity, const std::
|
||||
|
||||
node = rclcpp::Node::make_shared("moveService", topic);
|
||||
|
||||
#pragma clang diagnostic push
|
||||
#pragma ide diagnostic ignored "UnusedValue"
|
||||
animationServer = rclcpp_action::create_server<ign_actor_plugin::action::Animation>(
|
||||
node,
|
||||
"animation",
|
||||
@@ -58,12 +59,17 @@ void ActorSystem::Configure(const ignition::gazebo::Entity &_entity, const std::
|
||||
}
|
||||
);
|
||||
|
||||
movementServer rclcpp_action::create_server<ign_actor_plugin::action::Movement>(
|
||||
movementServer = rclcpp_action::create_server<ign_actor_plugin::action::Movement>(
|
||||
node,
|
||||
"movement",
|
||||
[](rclcpp_action::GoalUUID goalUuid, )
|
||||
)
|
||||
#pragma clang diagnostic pop
|
||||
[](rclcpp_action::GoalUUID goalUuid, MovementGoalPtr &movementGoal ){
|
||||
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
|
||||
},
|
||||
[](MovementServerGoalPtr goalUuid ){
|
||||
return rclcpp_action::CancelResponse::ACCEPT;
|
||||
},
|
||||
[](MovementServerGoalPtr goalUuid ){}
|
||||
);
|
||||
|
||||
printf("Spinning node...\n");
|
||||
std::thread spinThread([this]() {
|
||||
|
||||
Reference in New Issue
Block a user