Add last dangling changes before humble merge

This commit is contained in:
2022-11-22 10:05:06 +01:00
parent 6b650fe594
commit 9c0c189a23
4 changed files with 215 additions and 29 deletions

View File

@@ -50,13 +50,13 @@ namespace BT {
}
auto pose = std::make_shared<geometry_msgs::msg::Pose>();
pose->orientation.w=0;
pose->orientation.x=0;
pose->orientation.y=1;
pose->orientation.z=0;
pose->position.x= convertFromString<double>(parts[0]);
pose->position.y= convertFromString<double>(parts[1]);
pose->position.z= convertFromString<double>(parts[2]);
pose->orientation.w = 0;
pose->orientation.x = 0;
pose->orientation.y = 1;
pose->orientation.z = 0;
pose->position.x = convertFromString<double>(parts[0]);
pose->position.y = convertFromString<double>(parts[1]);
pose->position.z = convertFromString<double>(parts[2]);
std::cout << "[ generated pose from string ]" << std::endl;
@@ -71,9 +71,9 @@ namespace BT {
}
auto point = std::make_shared<geometry_msgs::msg::Point>();
point->x= convertFromString<double>(parts[0]);
point->y= convertFromString<double>(parts[1]);
point->z= convertFromString<double>(parts[2]);
point->x = convertFromString<double>(parts[0]);
point->y = convertFromString<double>(parts[1]);
point->z = convertFromString<double>(parts[2]);
return point;
}
@@ -86,10 +86,10 @@ namespace BT {
}
auto point = std::make_shared<geometry_msgs::msg::Quaternion>();
point->w= convertFromString<double>(parts[0]);
point->x= convertFromString<double>(parts[1]);
point->y= convertFromString<double>(parts[2]);
point->z= convertFromString<double>(parts[3]);
point->w = convertFromString<double>(parts[0]);
point->x = convertFromString<double>(parts[1]);
point->y = convertFromString<double>(parts[2]);
point->z = convertFromString<double>(parts[3]);
return point;
}

View File

@@ -247,12 +247,9 @@
<pose>0 1 1.25 0 0 0</pose>
<skin>
<filename>https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/walk.dae</filename>
<filename>/home/ros/go.dae</filename>
<scale>1.0</scale>
</skin>
<animation name="walk">
<filename>https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor/tip/files/meshes/walk.dae</filename>
</animation>
<plugin name="ActorSystem" filename="/home/ros/workspace/build/ign_actor_plugin/libActorPlugin.so">
<target>2 2 1</target>
<target_weight>1.15</target_weight>

View File

@@ -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]() {