Finally achieved parity with old implementation.

This commit is contained in:
Bastian Hofmann 2023-03-16 03:59:27 +00:00
parent 62d1c44613
commit 62dc1236f8
6 changed files with 27 additions and 24 deletions

View File

@ -3,6 +3,7 @@
//
#include "ActorMovement.h"
#include <action_msgs/msg/detail/goal_status__struct.hpp>
#include <behaviortree_cpp_v3/basic_types.h>
@ -54,10 +55,16 @@ BT::NodeStatus ActorMovement::onStart() {
mutex.unlock();
};
send_goal_options.goal_response_callback = [&](ClientGoalHandle<Movement>::SharedPtr parameter){
mutex.lock();
if(!parameter){
std::cout << "ActorMovement rejected by server." << std::endl;
result = BT::NodeStatus::FAILURE;
}else{
if (parameter->get_status() == action_msgs::msg::GoalStatus::STATUS_CANCELED || parameter->get_status() == action_msgs::msg::GoalStatus::STATUS_CANCELING ){
result = BT::NodeStatus::FAILURE;
}
}
mutex.unlock();
};
client->async_send_goal(goal,send_goal_options);

View File

@ -10,6 +10,7 @@ void MoveConnection::planAndExecute(const std::shared_ptr<geometry_msgs::msg::Po
const std::function<void(bool)> &callback) {
std::cout<<"planAndExecute."<<std::endl;
lock.lock();
state = RUNNING;
std::cout<<"got lock."<<std::endl;
lastTarget = pose;
lastCallback = callback;
@ -19,27 +20,21 @@ void MoveConnection::planAndExecute(const std::shared_ptr<geometry_msgs::msg::Po
std::cout<<"Starting planning"<<std::endl;
std::thread([this,callback,pose](){
moveGroup.setPoseTarget(*pose);
std::thread([&](){
moveGroup.setPoseTarget(*lastTarget);
moveGroup.setGoalJointTolerance(0.01);
moveGroup.setGoalOrientationTolerance(0.01);
std::cout<<"Parameters set."<<std::endl;
moveit::planning_interface::MoveGroupInterface::Plan plan;
if(moveGroup.plan(plan)==moveit::core::MoveItErrorCode::SUCCESS){
std::cout<<"Planned a path."<<std::endl;
}else{
std::cout<<"Error during planning."<<std::endl;
lastTarget = nullptr;
lock.unlock();
callback(false);
return;
}
callback( moveGroup.execute(plan) == moveit::core::MoveItErrorCode::SUCCESS );
auto finished = moveGroup.move() == moveit::core::MoveItErrorCode::SUCCESS;
lastTarget = nullptr;
if(state!=SPEED_CHANGE){
lastCallback( finished );
lastTarget = nullptr;
}
state = IDLE;
lock.unlock();
}).detach();
}
@ -51,6 +46,7 @@ void MoveConnection::setSpeedMultiplier(const double speed){
auto target = lastTarget;
auto callback = lastCallback;
if (target != nullptr) {
state = SPEED_CHANGE;
stop();
std::cout<<"Restarting"<<std::endl;
planAndExecute(target, callback);
@ -60,11 +56,9 @@ void MoveConnection::setSpeedMultiplier(const double speed){
void MoveConnection::stop() {
std::cout<<"Stopping MoveConnection"<<std::endl;
cancelled = true;
if(rclcpp::ok()){
while (rclcpp::ok() && state!=IDLE){
moveGroup.stop();
while (lastTarget != nullptr) {}
usleep(1000);
}
cancelled = false;
std::cout<<"Stopped MoveConnection"<<std::endl;
}

View File

@ -12,10 +12,10 @@
class MoveConnection {
private:
enum {IDLE,RUNNING,SPEED_CHANGE} state;
moveit::planning_interface::MoveGroupInterface moveGroup;
std::shared_ptr<geometry_msgs::msg::Pose> lastTarget = nullptr;
std::function<void(bool)> lastCallback = [](bool finished) {};
bool cancelled=false;
std::function<void(bool)> lastCallback = [](__attribute__((unused))bool finished) {};
double currentSpeed = 1;
std::mutex lock;
public:

View File

@ -11,6 +11,7 @@ BT::RobotMove::RobotMove(const std::string &name, const BT::NodeConfiguration &c
}
BT::NodeStatus BT::RobotMove::onStart() {
std::cout << "Starting RobotMove" << std::endl;
std::shared_ptr<geometry_msgs::msg::Pose> pose;
if(!getInput<std::shared_ptr<geometry_msgs::msg::Pose>>("target",pose)){
std::cout << "no target available." << std::endl;
@ -38,8 +39,9 @@ BT::NodeStatus BT::RobotMove::onRunning() {
}
void BT::RobotMove::onHalted() {
std::cout << "Halting RobotMove" << std::endl;
connection->get()->stop();
asyncResult=NodeStatus::IDLE;
asyncResult=NodeStatus::FAILURE;
}
BT::PortsList BT::RobotMove::providedPorts() {

View File

@ -80,7 +80,7 @@ int main(int argc, char **argv) {
FeedbackMessage currentFeedback;
ActionMessage currentAction;
std::thread([feedbackQueue, &currentAnimationGoalPtr, &currentMovementGoalPtr, &currentFeedback, &currentAction] {
std::thread([feedbackQueue, &currentAnimationGoalPtr, &currentMovementGoalPtr, &currentFeedback] {
while (true) {
FeedbackMessage newFeedback;
if(mq_receive(feedbackQueue, (char *)&newFeedback, sizeof(ros_actor_message_queue_msgs::FeedbackMessage), nullptr)==-1){