Final version of actor plugin

This commit is contained in:
Bastian Hofmann
2023-02-14 17:03:17 +00:00
parent bf36c02d2a
commit 17e61a505f
19 changed files with 579 additions and 548 deletions

View File

@@ -10,33 +10,36 @@ find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(ignition-cmake2 REQUIRED)
find_package(ignition-gazebo6 REQUIRED)
find_package(ign_actor_plugin_msgs REQUIRED)
find_package(ros_actor_message_queue_msgs REQUIRED)
find_package(ros_actor_action_server_msgs REQUIRED)
find_package(ignition-plugin1 REQUIRED COMPONENTS register)
set(IGN_PLUGIN_VER ${ignition-plugin1_VERSION_MAJOR})
ament_export_dependencies(ActorPlugin
"rosidl_default_runtime"
"ign_actor_plugin_msgs"
"rclcpp"
"rclcpp_action"
"rclcpp_components")
ament_export_dependencies(ign_actor_plugin
"rosidl_default_runtime"
"ros_actor_action_server_msgs"
"rclcpp"
"rclcpp_action"
"rclcpp_components"
)
# Add sources for each plugin to be registered.
add_library(ActorPlugin SHARED src/ActorSystem.cpp)
ament_target_dependencies(ActorPlugin rclcpp rclcpp_action ign_actor_plugin_msgs)
set_property(TARGET ActorPlugin PROPERTY CXX_STANDARD 17)
target_compile_options(ActorPlugin PRIVATE -std=c++17)
add_library(ign_actor_plugin SHARED src/ActorSystem.cpp)
ament_target_dependencies(ign_actor_plugin rclcpp rclcpp_action ros_actor_message_queue_msgs ros_actor_action_server_msgs)
set_property(TARGET ign_actor_plugin PROPERTY CXX_STANDARD 17)
target_compile_options(ign_actor_plugin PRIVATE -std=c++17)
target_link_libraries(ActorPlugin
ignition-gazebo6::ignition-gazebo6
ignition-plugin${IGN_PLUGIN_VER}::ignition-plugin${IGN_PLUGIN_VER}
${rclcpp_LIBRARIES}
${rclcpp_action_LIBRARIES}
)
target_link_libraries(ign_actor_plugin
ignition-gazebo6::ignition-gazebo6
ignition-plugin${IGN_PLUGIN_VER}::ignition-plugin${IGN_PLUGIN_VER}
${rclcpp_LIBRARIES}
${rclcpp_action_LIBRARIES}
)
install(TARGETS
ActorPlugin
DESTINATION lib/${PROJECT_NAME})
ign_actor_plugin
DESTINATION lib/${PROJECT_NAME}
)
ament_package()

View File

@@ -11,7 +11,8 @@
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>rclcpp_components</depend>
<depend>ign_actor_plugin_msgs</depend>
<depend>ros_actor_message_queue_msgs</depend>
<depend>ros_actor_action_server_msgs</depend>
<depend>ignition-cmake2</depend>
<depend>ignition-gazebo6</depend>
<test_depend>ament_lint_auto</test_depend>

View File

@@ -2,42 +2,37 @@
// Created by bastian on 31.08.22.
//
#include "ActorSystem.hpp"
#include <chrono>
#include <ign_actor_plugin_msgs/action/detail/animation__struct.hpp>
#include <cstdio>
#include <fcntl.h>
#include <ignition/common/Console.hh>
#include <ignition/common/Mesh.hh>
#include <ignition/common/MeshManager.hh>
#include <ignition/common/SkeletonAnimation.hh>
#include <ignition/gazebo/Entity.hh>
#include <ignition/gazebo/EntityComponentManager.hh>
#include <ignition/gazebo/Types.hh>
#include <ignition/gazebo/components/Actor.hh>
#include <ignition/gazebo/components/Component.hh>
#include <ignition/gazebo/components/Pose.hh>
#include <rclcpp_action/create_server.hpp>
#include <rclcpp_action/server.hpp>
#include "ActorSystem.hpp"
#include <ignition/gazebo/components/Actor.hh>
#include <ignition/gazebo/EntityComponentManager.hh>
#include <sdf/Actor.hh>
#include <ignition/common/MeshManager.hh>
#include <ignition/common/SkeletonAnimation.hh>
#include <ignition/common/Mesh.hh>
#include <sys/mman.h>
#include <fcntl.h>
#include <cstdio>
#include <unistd.h>
IGNITION_ADD_PLUGIN(
ignition::gazebo::ActorSystem,
ignition::gazebo::System,
ignition::gazebo::ActorSystem::ISystemPreUpdate,
ignition::gazebo::ActorSystem::ISystemConfigure)
IGNITION_ADD_PLUGIN(ignition::gazebo::ActorSystem, ignition::gazebo::System, ignition::gazebo::ActorSystem::ISystemPreUpdate,
ignition::gazebo::ActorSystem::ISystemConfigure)
using namespace ignition::gazebo;
using namespace ign_actor_plugin_msgs;
using namespace ros_actor_action_server_msgs;
ActorSystem::ActorSystem() = default;
ActorSystem::~ActorSystem() = default;
void ActorSystem::switchAnimation(EntityComponentManager &_ecm, char* animationName){
void ActorSystem::switchAnimation(EntityComponentManager &_ecm, char *animationName) {
igndbg << "Initial setup for new animation." << std::endl;
auto actorComp = _ecm.Component<components::Actor>(entity);
@@ -51,15 +46,15 @@ void ActorSystem::switchAnimation(EntityComponentManager &_ecm, char* animationN
_ecm.SetChanged(entity, components::AnimationTime::typeId, ComponentState::OneTimeChange);
int foundAnimationIndex = -1;
for (int animationIndex = 0 ; animationIndex < actorComp->Data().AnimationCount() ; animationIndex++) {
for (int animationIndex = 0; animationIndex < actorComp->Data().AnimationCount(); animationIndex++) {
auto animation = actorComp->Data().AnimationByIndex(animationIndex);
if (animation->Name() == animationName){
if (animation->Name() == animationName) {
foundAnimationIndex = animationIndex;
break;
}
}
if(foundAnimationIndex != -1){
if (foundAnimationIndex != -1) {
igndbg << "Found animation to play" << std::endl;
auto fileName = actorComp->Data().AnimationByIndex(foundAnimationIndex)->Filename();
@@ -77,317 +72,230 @@ void ActorSystem::switchAnimation(EntityComponentManager &_ecm, char* animationN
igndbg << "Translation: " << currentTranslationAlign << std::endl;
igndbg << "Rotation: " << currentRotationAlign << std::endl;
if (currentSkeleton != nullptr){
if (currentSkeleton != nullptr) {
duration = currentSkeleton->Animation(0)->Length();
igndbg << "length: " << duration << " seconds." << std::endl;
} else {
ignerr << "No skeleton found!" << std::endl;
}
auto initialPose = currentRootNodeAnimation -> FrameAt(0).Pose();
auto initialPose = currentRootNodeAnimation->FrameAt(0).Pose();
auto poseComponent = _ecm.Component<components::Pose>(entity);
auto newPose = initialPose;
newPose.Pos().X(0);
newPose.Pos().Y(0);
*poseComponent = components::Pose(newPose);
} else {
ignerr << "No animation found!" << std::endl;
ignerr << "No animation found!" << std::endl;
}
}
void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) {
pthread_mutex_lock(&shared_mmap->mutex);
switch(shared_mmap->currentState){
case SETUP: {
igndbg << "Setting up actor plugin" << std::endl;
threadMutex.lock();
auto actorComponent = _ecm.Component<components::Actor>(entity);
auto animationNameComponent = _ecm.Component<components::AnimationName>(entity);
if (nullptr == animationNameComponent) {
_ecm.CreateComponent(entity, components::AnimationName(actorComponent->Data().AnimationByIndex(0)->Name()));
}
switch (currentState) {
case SETUP: {
igndbg << "Setting up actor plugin" << std::endl;
auto animTimeComponent = _ecm.Component<components::AnimationTime>(entity);
if (nullptr == animTimeComponent) {
_ecm.CreateComponent(entity, components::AnimationTime());
}
auto actorComponent = _ecm.Component<components::Actor>(entity);
auto poseComponent = _ecm.Component<components::Pose>(entity);
if (nullptr == poseComponent) {
_ecm.CreateComponent(entity, components::Pose(ignition::math::Pose3d::Zero));
}
auto trajectoryPoseComponent = _ecm.Component<components::TrajectoryPose>(entity);
if (nullptr == trajectoryPoseComponent) {
_ecm.CreateComponent(entity, components::TrajectoryPose(ignition::math::Pose3d::Zero));
}
shared_mmap->currentState = ActorSystemState::IDLE;
break;
auto animationNameComponent = _ecm.Component<components::AnimationName>(entity);
if (nullptr == animationNameComponent) {
_ecm.CreateComponent(entity, components::AnimationName(actorComponent->Data().AnimationByIndex(0)->Name()));
}
case ANIMATION: {
if (shared_mmap->lastState == ActorSystemState::IDLE){
switchAnimation(_ecm, shared_mmap->animation_name);
}
auto animationTimeComponent = _ecm.Component<components::AnimationTime>(this->entity);
auto newTime = animationTimeComponent->Data() + _info.dt;
auto newTimeSeconds = std::chrono::duration<double>(newTime).count();
auto feedback = (float) (newTimeSeconds/duration);
write(feedback_pipe[1],&feedback,sizeof(float));
//currentAnimationGoalPtr->publish_feedback(feedback);
if (newTimeSeconds >= duration){
//currentAnimationGoalPtr->succeed(std::make_shared<action::Animation::Result>());
igndbg << "Animation " << shared_mmap->animation_name << " finished." << std::endl;
shared_mmap->currentState = ActorSystemState::IDLE;
break;
}
*animationTimeComponent = components::AnimationTime(newTime);
_ecm.SetChanged(entity, components::AnimationTime::typeId, ComponentState::OneTimeChange);
/*
if(currentRootNodeAnimation == nullptr){
break;
}
auto rootTransformation = currentRootNodeAnimation->FrameAt(newTimeSeconds,false);
math::Matrix4d totalTf = currentTranslationAlign * rootTransformation * currentRotationAlign;
auto translation = totalTf.Translation();
translation[0] = 0;
totalTf.SetTranslation(translation);
auto poseComp = _ecm.Component<components::Pose>(entity);
*poseComp = components::Pose (totalTf.Pose());
_ecm.SetChanged(entity, components::Pose::typeId, ComponentState::OneTimeChange);
*/
break;
auto animTimeComponent = _ecm.Component<components::AnimationTime>(entity);
if (nullptr == animTimeComponent) {
_ecm.CreateComponent(entity, components::AnimationTime());
}
case MOVEMENT:{
if (shared_mmap->lastState == ActorSystemState::IDLE){
igndbg << "Starting Movement..." << std::endl;
switchAnimation(_ecm, shared_mmap->animation_name);
}
auto trajectoryPoseComp = _ecm.Component<components::TrajectoryPose>(this->entity);
auto actorPose = trajectoryPoseComp->Data();
auto targetPose = shared_mmap->target_position;
auto targetDirection = math::Vector3d(targetPose[0],targetPose[1],targetPose[2]) - actorPose.Pos();
if (targetDirection.Length()<0.05){
float feedback = 1.0f;
write(feedback_pipe[1],&feedback,sizeof(float));
//currentMovementGoalPtr->succeed(std::make_shared<action::Movement::Result>());
shared_mmap->currentState = ActorSystemState::IDLE;
break;
}
auto animationTimeComponent = _ecm.Component<components::AnimationTime>(this->entity);
auto oldTimeSeconds = std::chrono::duration<double>(animationTimeComponent->Data()).count();
auto deltaTimeSeconds = std::chrono::duration<double>(_info.dt).count();
auto newTimeSeconds = oldTimeSeconds + deltaTimeSeconds;
auto newTime = animationTimeComponent->Data() + _info.dt;
if(newTimeSeconds >= duration){
newTimeSeconds -= duration;
newTime = std::chrono::duration_cast<std::chrono::steady_clock::duration>(std::chrono::duration<double>(newTimeSeconds));
}
auto targetYaw = atan2(targetDirection.Y(),targetDirection.X());
auto currentYaw = fmod(actorPose.Rot().Yaw(),M_PI);
auto angularDirection = fmod((targetYaw - currentYaw), M_PI+0.001); // additional 0.001 rad to prevent instant flip through 180 rotation
auto turnSpeed = 1.0;
if (angularDirection < 0){
turnSpeed = -turnSpeed;
}
if (abs(angularDirection) > 0.01){
actorPose.Rot().Euler(0,0,actorPose.Rot().Yaw()+(turnSpeed*deltaTimeSeconds));
*trajectoryPoseComp = components::TrajectoryPose(actorPose);
_ecm.SetChanged(entity, components::TrajectoryPose::typeId, ComponentState::OneTimeChange);
}else{
if (nullptr == currentRootNodeAnimation){
ignerr << "Current animation doesn't move root node, this is unsupported for movement animations." << std::endl;
break;
}
double distance = (deltaTimeSeconds/duration)*shared_mmap->animation_distance;
actorPose.Pos() += targetDirection.Normalize() * distance;
actorPose.Rot().Euler(0,0,targetYaw);
*trajectoryPoseComp = components::TrajectoryPose(actorPose);
*animationTimeComponent = components::AnimationTime(newTime);
_ecm.SetChanged(entity, components::TrajectoryPose::typeId, ComponentState::OneTimeChange);
_ecm.SetChanged(entity, components::AnimationTime::typeId, ComponentState::OneTimeChange);
}
break;
auto poseComponent = _ecm.Component<components::Pose>(entity);
if (nullptr == poseComponent) {
_ecm.CreateComponent(entity, components::Pose(ignition::math::Pose3d::Zero));
}
case IDLE:
if (shared_mmap->lastState != shared_mmap->currentState){
igndbg << "Now idling..." << std::endl;
}
break;
auto trajectoryPoseComponent = _ecm.Component<components::TrajectoryPose>(entity);
if (nullptr == trajectoryPoseComponent) {
_ecm.CreateComponent(entity, components::TrajectoryPose(ignition::math::Pose3d::Zero));
}
currentState = IDLE;
break;
}
shared_mmap->lastState = shared_mmap->currentState;
pthread_mutex_unlock(&shared_mmap->mutex);
case ANIMATION: {
if (lastState == IDLE) {
switchAnimation(_ecm, animation_name);
}
auto animationTimeComponent = _ecm.Component<components::AnimationTime>(this->entity);
auto newTime = animationTimeComponent->Data() + _info.dt;
auto newTimeSeconds = std::chrono::duration<double>(newTime).count();
auto feedback = newTimeSeconds / duration;
sendFeedback(feedback);
if (newTimeSeconds >= duration) {
igndbg << "Animation " << animation_name << " finished." << std::endl;
currentState = IDLE;
break;
}
*animationTimeComponent = components::AnimationTime(newTime);
_ecm.SetChanged(entity, components::AnimationTime::typeId, ComponentState::OneTimeChange);
/*
if(currentRootNodeAnimation == nullptr){
break;
}
auto rootTransformation = currentRootNodeAnimation->FrameAt(newTimeSeconds,false);
math::Matrix4d totalTf = currentTranslationAlign * rootTransformation * currentRotationAlign;
auto translation = totalTf.Translation();
translation[0] = 0;
totalTf.SetTranslation(translation);
auto poseComp = _ecm.Component<components::Pose>(entity);
*poseComp = components::Pose (totalTf.Pose());
_ecm.SetChanged(entity, components::Pose::typeId, ComponentState::OneTimeChange);
*/
break;
}
case MOVEMENT: {
if (lastState == IDLE) {
igndbg << "Starting Movement..." << std::endl;
switchAnimation(_ecm, animation_name);
}
auto trajectoryPoseComp = _ecm.Component<components::TrajectoryPose>(this->entity);
auto actorPose = trajectoryPoseComp->Data();
auto targetPose = target_position;
auto targetDirection = math::Vector3d(targetPose[0], targetPose[1], targetPose[2]) - actorPose.Pos();
if (targetDirection.Length() < 0.05) {
sendFeedback(1.0);
currentState = IDLE;
break;
}
auto animationTimeComponent = _ecm.Component<components::AnimationTime>(this->entity);
auto oldTimeSeconds = std::chrono::duration<double>(animationTimeComponent->Data()).count();
auto deltaTimeSeconds = std::chrono::duration<double>(_info.dt).count();
auto newTimeSeconds = oldTimeSeconds + deltaTimeSeconds;
auto newTime = animationTimeComponent->Data() + _info.dt;
if (newTimeSeconds >= duration) {
newTimeSeconds -= duration;
newTime = std::chrono::duration_cast<std::chrono::steady_clock::duration>(std::chrono::duration<double>(newTimeSeconds));
}
auto targetYaw = atan2(targetDirection.Y(), targetDirection.X());
auto currentYaw = fmod(actorPose.Rot().Yaw(), M_PI);
auto angularDirection = fmod((targetYaw - currentYaw),
M_PI + 0.001); // additional 0.001 rad to prevent instant flip through 180 rotation
auto turnSpeed = 1.0;
if (angularDirection < 0) {
turnSpeed = -turnSpeed;
}
if (abs(angularDirection) > 0.01) {
actorPose.Rot().Euler(0, 0, actorPose.Rot().Yaw() + (turnSpeed * deltaTimeSeconds));
*trajectoryPoseComp = components::TrajectoryPose(actorPose);
_ecm.SetChanged(entity, components::TrajectoryPose::typeId, ComponentState::OneTimeChange);
} else {
if (nullptr == currentRootNodeAnimation) {
ignerr << "Current animation doesn't move root node, this is unsupported for movement animations." << std::endl;
break;
}
double distance = (deltaTimeSeconds / duration) * animation_distance;
actorPose.Pos() += targetDirection.Normalize() * distance;
actorPose.Rot().Euler(0, 0, targetYaw);
*trajectoryPoseComp = components::TrajectoryPose(actorPose);
*animationTimeComponent = components::AnimationTime(newTime);
_ecm.SetChanged(entity, components::TrajectoryPose::typeId, ComponentState::OneTimeChange);
_ecm.SetChanged(entity, components::AnimationTime::typeId, ComponentState::OneTimeChange);
}
break;
}
case IDLE:
break;
}
if (lastState != currentState) {
igndbg << "State change: " << lastState << " -> " << currentState << std::endl;
sendFeedback(0.0);
}
lastState = currentState;
threadMutex.unlock();
}
void ActorSystem::messageQueueInterface(const char name[256]) {
mq_attr queueAttributes;
queueAttributes.mq_flags = 0;
queueAttributes.mq_curmsgs = 0;
queueAttributes.mq_msgsize = sizeof(ros_actor_message_queue_msgs::FeedbackMessage);
queueAttributes.mq_maxmsg = 1;
char generatedName[256];
strcpy(generatedName,name);
strcat(generatedName,"Feedback");
feedbackQueue = mq_open(generatedName, O_CREAT | O_RDWR, S_IRWXU | S_IRWXG, &queueAttributes);
void ActorSystem::rclcppServer(const std::string& topic){
rclcpp::init(0, {});
auto node = rclcpp::Node::make_shared("moveService", topic);
AnimationServerGoalPtr currentAnimationGoalPtr;
MovementServerGoalPtr currentMovementGoalPtr;
#pragma clang diagnostic push
#pragma ide diagnostic ignored "UnusedValue"
auto animationServer = rclcpp_action::create_server<action::Animation>(
node,
"animation",
[this](const rclcpp_action::GoalUUID goalUuid, const AnimationGoalPtr &animationGoal) {
igndbg << "goal" << shared_mmap->currentState << std::endl;
if (shared_mmap->currentState == ActorSystemState::IDLE) {
pthread_mutex_lock(&shared_mmap->mutex);
igndbg << "goal l" << shared_mmap->currentState << std::endl;
strcpy(shared_mmap->animation_name,animationGoal->animation_name.data());
pthread_mutex_unlock(&shared_mmap->mutex);
return rclcpp_action::GoalResponse::ACCEPT_AND_DEFER;
}else{
return rclcpp_action::GoalResponse::REJECT;
}
},
[this](const AnimationServerGoalPtr& animationGoalPtr) {
igndbg << "cancel" << shared_mmap->currentState << std::endl;
if (shared_mmap->currentState == ActorSystemState::IDLE) {
return rclcpp_action::CancelResponse::REJECT;
}else{
pthread_mutex_lock(&shared_mmap->mutex);
shared_mmap->currentState = ActorSystemState::IDLE;
pthread_mutex_unlock(&shared_mmap->mutex);
return rclcpp_action::CancelResponse::ACCEPT;
}
},
[this,&currentAnimationGoalPtr](const AnimationServerGoalPtr& animationGoalPtr) {
igndbg << "accepted" << shared_mmap->currentState << std::endl;
pthread_mutex_lock(&shared_mmap->mutex);
igndbg << "accepted l" << shared_mmap->currentState << std::endl;
igndbg << "got animation handle" << std::endl;
currentAnimationGoalPtr = animationGoalPtr;
shared_mmap->currentState = ActorSystemState::ANIMATION;
currentAnimationGoalPtr->execute();
pthread_mutex_unlock(&shared_mmap->mutex);
}
);
auto movementServer = rclcpp_action::create_server<action::Movement>(
node,
"movement",
[this](const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal ){
if (shared_mmap->currentState == ActorSystemState::IDLE) {
pthread_mutex_lock(&shared_mmap->mutex);
shared_mmap->target_position = math::Vector3d(
movementGoal->target_position[0],
movementGoal->target_position[1],
movementGoal->target_position[2]);
shared_mmap->animation_distance = movementGoal->animation_distance;
strcpy(shared_mmap->animation_name,movementGoal->animation_name.data());
pthread_mutex_unlock(&shared_mmap->mutex);
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}else{
return rclcpp_action::GoalResponse::REJECT;
}
},
[this](const MovementServerGoalPtr& movementGoalPtr ){
if (shared_mmap->currentState == ActorSystemState::IDLE) {
return rclcpp_action::CancelResponse::REJECT;
}else{
pthread_mutex_lock(&shared_mmap->mutex);
shared_mmap->currentState = ActorSystemState::IDLE;
pthread_mutex_unlock(&shared_mmap->mutex);
return rclcpp_action::CancelResponse::ACCEPT;
}
},
[this,&currentMovementGoalPtr](const MovementServerGoalPtr& movementGoalPtr ){
pthread_mutex_lock(&shared_mmap->mutex);
igndbg << "got movement handle" << std::endl;
currentMovementGoalPtr = movementGoalPtr;
shared_mmap->currentState = ActorSystemState::MOVEMENT;
pthread_mutex_unlock(&shared_mmap->mutex);
}
);
#pragma clang diagnostic pop
std::thread t([this,&currentAnimationGoalPtr,&currentMovementGoalPtr]() {
float progress;
while(true) {
read(feedback_pipe[0], &progress, sizeof(float));
igndbg << progress << std::endl;
if(progress >= 1.0f){
if(currentAnimationGoalPtr!=nullptr){
currentAnimationGoalPtr->succeed(std::make_shared<action::Animation::Result>());
}
if(currentMovementGoalPtr!=nullptr){
currentMovementGoalPtr->succeed(std::make_shared<action::Movement::Result>());
}
}else{
if(currentAnimationGoalPtr!=nullptr){
auto feedback = std::make_shared<action::Animation::Feedback>();
feedback->set__progress(progress);
currentAnimationGoalPtr->publish_feedback(feedback);
}
if(currentMovementGoalPtr!=nullptr){
auto feedback = std::make_shared<action::Movement::Feedback>();
feedback->set__progress(progress);
currentMovementGoalPtr->publish_feedback(feedback);
}
}
usleep(500);
}
});
t.detach();
igndbg << "Spinning node..." << std::endl;
while (true) {
printf("Spinning...\n");
rclcpp::spin(node);
if (feedbackQueue == (mqd_t)-1) {
ignerr << "Could not create queue. (" << errno << ")" << std::endl;
return;
}
strcpy(generatedName,name);
strcat(generatedName,"Action");
queueAttributes.mq_msgsize = sizeof(ros_actor_message_queue_msgs::ActionMessage);
actionQueue = mq_open(generatedName, O_CREAT | O_RDWR, S_IRWXU | S_IRWXG, &queueAttributes);
if (actionQueue == (mqd_t)-1) {
ignerr << "Could not create queue. (" << errno << ")" << std::endl;
return;
}
std::thread([this] {
ActionMessage receivedAction;
while (true) {
mq_receive(actionQueue, (char *)&receivedAction, sizeof(ActionMessage), nullptr);
threadMutex.lock();
strcpy(animation_name, receivedAction.animationName);
// animation_speed = receivedAction.animationSpeed;
animation_distance = receivedAction.animationDistance;
target_position = math::Vector3d(receivedAction.positionX, receivedAction.positionY, receivedAction.positionZ);
currentState = receivedAction.state;
std::cout << "Got Action" << std::endl;
threadMutex.unlock();
}
}).detach();
}
void ActorSystem::sendFeedback(double progress){
FeedbackMessage message;
message.progress = progress;
message.state = currentState;
mq_send(feedbackQueue,(char *)&message,sizeof(FeedbackMessage),0);
}
// Found too late: https://github.com/AlanSixth/gazebo_ros_action_tutorial/blob/master/src/gazebo_ros_action_tutorial.cc
// https://github.com/gazebosim/gz-sim/blob/ign-gazebo6/src/systems/follow_actor/FollowActor.cc
void ActorSystem::Configure(const Entity &_entity, const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &_ecm, EventManager &) {
void ActorSystem::Configure(const Entity &_entity, const std::shared_ptr<const sdf::Element> &_sdf, EntityComponentManager &_ecm,
EventManager &) {
igndbg << "actor plugin configuring..." << std::endl;
auto actorComp = _ecm.Component<components::Actor>(_entity);
@@ -396,62 +304,20 @@ void ActorSystem::Configure(const Entity &_entity, const std::shared_ptr<const s
return;
}
std::string topic = "ActorPlugin";
char topic[256] = "/ActorPlugin";
if (_sdf->HasElement("topic")) {
topic = _sdf->Get<std::string>("topic");
auto topicString = _sdf->Get<std::string>("topic");
if (topicString.size() >= 256) {
ignerr << "queue name too long, not starting plugin!";
return;
}
strcpy(topic, topicString.c_str());
}
this->entity = _entity;
igndbg << "shmem setup" << std::endl;
int fd = open(".", O_TMPFILE|O_RDWR, 00600);
auto structSize = sizeof(struct sharedMmap);
if(ftruncate(fd, structSize)!=0){
ignerr << "ftruncate" << std::endl;
return;
}
shared_mmap = (struct sharedMmap *) mmap(nullptr,structSize,PROT_READ|PROT_WRITE,MAP_SHARED,fd,0);
//close(fd);
messageQueueInterface(topic);
if (shared_mmap == MAP_FAILED){
ignerr << "MAP_FAILED" << std::endl;
return;
}
pthread_mutexattr_t mutexattr;
if(pthread_mutexattr_init(&mutexattr)!=0){
ignerr << "pthread_mutexattr_init" << std::endl;
return;
}
if(pthread_mutexattr_setpshared(&mutexattr, PTHREAD_PROCESS_SHARED)!=0){
ignerr << "pthread_mutexattr_setpshared" << std::endl;
return;
}
if(pthread_mutex_init(&shared_mmap->mutex, &mutexattr)!=0){
ignerr << "pthread_mutex_init" << std::endl;
return;
}
shared_mmap->currentState = ActorSystemState::SETUP;
shared_mmap->lastState = ActorSystemState::IDLE;
igndbg << "pipe setup" << std::endl;
if (pipe(feedback_pipe)!=0){
igndbg << "pipe failed." << std::endl;
return;
}
switch(fork()){
case -1:
ignerr << "Could not fork." << std::endl;
break;
case 0:
ignmsg << "Child fork." << std::endl;
rclcppServer(topic);
break;
default:
ignmsg << "Parent fork." << std::endl;
break;
}
currentState = SETUP;
lastState = SETUP;
}

View File

@@ -14,14 +14,19 @@
#include <rclcpp/node.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/server.hpp>
#include <ign_actor_plugin_msgs/action/animation.hpp>
#include <ign_actor_plugin_msgs/action/movement.hpp>
#include <ros_actor_action_server_msgs/action/animation.hpp>
#include <ros_actor_action_server_msgs/action/movement.hpp>
#include <ros_actor_message_queue_msgs/MessageTypes.hpp>
#include <rclcpp_action/server_goal_handle.hpp>
#include <string>
#include <ignition/common/Skeleton.hh>
#include <ignition/common/NodeAnimation.hh>
#include <fcntl.h>
#include <sys/stat.h>
#include <mqueue.h>
using namespace ign_actor_plugin_msgs;
using namespace ros_actor_message_queue_msgs;
using namespace ros_actor_action_server_msgs;
using rclcpp_action::ServerGoalHandle;
#define AnimationActionServer rclcpp_action::Server<action::Animation>
@@ -35,17 +40,6 @@ using rclcpp_action::ServerGoalHandle;
namespace ignition {
namespace gazebo {
enum ActorSystemState {
SETUP, IDLE, MOVEMENT, ANIMATION
};
struct sharedMmap{
pthread_mutex_t mutex;
ActorSystemState currentState,lastState;
char animation_name[256];
double animation_distance;
math::Vector3d target_position;
};
class ActorSystem :
public System,
@@ -61,14 +55,18 @@ namespace ignition {
//action::Movement::Goal movementTarget;
//AnimationServerGoalPtr currentAnimationGoalPtr;
//MovementServerGoalPtr currentMovementGoalPtr;
math::Vector3d target_position;
double animation_distance;
char animation_name[256];
ActorPluginState currentState,lastState;
double duration{};
Entity entity{kNullEntity};
//std::mutex threadMutex;
std::mutex threadMutex;
std::shared_ptr<common::Skeleton> currentSkeleton;
common::NodeAnimation* currentRootNodeAnimation;
math::Matrix4<double> currentRotationAlign, currentTranslationAlign;
struct sharedMmap* shared_mmap;
int feedback_pipe[2];
mqd_t feedbackQueue;
mqd_t actionQueue;
public:
ActorSystem();
@@ -88,7 +86,8 @@ namespace ignition {
private:
void switchAnimation(EntityComponentManager &_ecm, char *animationName);
void rclcppServer(const std::string& topic);
void messageQueueInterface(const char name[256]);
void sendFeedback(double feedback);
};