Finally achieved parity with old implementation.
This commit is contained in:
parent
62d1c44613
commit
62dc1236f8
@ -3,6 +3,7 @@
|
|||||||
//
|
//
|
||||||
|
|
||||||
#include "ActorMovement.h"
|
#include "ActorMovement.h"
|
||||||
|
#include <action_msgs/msg/detail/goal_status__struct.hpp>
|
||||||
#include <behaviortree_cpp_v3/basic_types.h>
|
#include <behaviortree_cpp_v3/basic_types.h>
|
||||||
|
|
||||||
|
|
||||||
@ -54,10 +55,16 @@ BT::NodeStatus ActorMovement::onStart() {
|
|||||||
mutex.unlock();
|
mutex.unlock();
|
||||||
};
|
};
|
||||||
send_goal_options.goal_response_callback = [&](ClientGoalHandle<Movement>::SharedPtr parameter){
|
send_goal_options.goal_response_callback = [&](ClientGoalHandle<Movement>::SharedPtr parameter){
|
||||||
|
mutex.lock();
|
||||||
if(!parameter){
|
if(!parameter){
|
||||||
std::cout << "ActorMovement rejected by server." << std::endl;
|
std::cout << "ActorMovement rejected by server." << std::endl;
|
||||||
result = BT::NodeStatus::FAILURE;
|
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);
|
client->async_send_goal(goal,send_goal_options);
|
||||||
|
|||||||
@ -10,6 +10,7 @@ void MoveConnection::planAndExecute(const std::shared_ptr<geometry_msgs::msg::Po
|
|||||||
const std::function<void(bool)> &callback) {
|
const std::function<void(bool)> &callback) {
|
||||||
std::cout<<"planAndExecute."<<std::endl;
|
std::cout<<"planAndExecute."<<std::endl;
|
||||||
lock.lock();
|
lock.lock();
|
||||||
|
state = RUNNING;
|
||||||
std::cout<<"got lock."<<std::endl;
|
std::cout<<"got lock."<<std::endl;
|
||||||
lastTarget = pose;
|
lastTarget = pose;
|
||||||
lastCallback = callback;
|
lastCallback = callback;
|
||||||
@ -19,27 +20,21 @@ void MoveConnection::planAndExecute(const std::shared_ptr<geometry_msgs::msg::Po
|
|||||||
|
|
||||||
std::cout<<"Starting planning"<<std::endl;
|
std::cout<<"Starting planning"<<std::endl;
|
||||||
|
|
||||||
std::thread([this,callback,pose](){
|
std::thread([&](){
|
||||||
|
moveGroup.setPoseTarget(*lastTarget);
|
||||||
moveGroup.setPoseTarget(*pose);
|
|
||||||
moveGroup.setGoalJointTolerance(0.01);
|
moveGroup.setGoalJointTolerance(0.01);
|
||||||
moveGroup.setGoalOrientationTolerance(0.01);
|
moveGroup.setGoalOrientationTolerance(0.01);
|
||||||
|
|
||||||
std::cout<<"Parameters set."<<std::endl;
|
std::cout<<"Parameters set."<<std::endl;
|
||||||
|
|
||||||
moveit::planning_interface::MoveGroupInterface::Plan plan;
|
auto finished = moveGroup.move() == moveit::core::MoveItErrorCode::SUCCESS;
|
||||||
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 );
|
|
||||||
|
|
||||||
lastTarget = nullptr;
|
if(state!=SPEED_CHANGE){
|
||||||
|
lastCallback( finished );
|
||||||
|
lastTarget = nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
state = IDLE;
|
||||||
lock.unlock();
|
lock.unlock();
|
||||||
}).detach();
|
}).detach();
|
||||||
}
|
}
|
||||||
@ -51,6 +46,7 @@ void MoveConnection::setSpeedMultiplier(const double speed){
|
|||||||
auto target = lastTarget;
|
auto target = lastTarget;
|
||||||
auto callback = lastCallback;
|
auto callback = lastCallback;
|
||||||
if (target != nullptr) {
|
if (target != nullptr) {
|
||||||
|
state = SPEED_CHANGE;
|
||||||
stop();
|
stop();
|
||||||
std::cout<<"Restarting"<<std::endl;
|
std::cout<<"Restarting"<<std::endl;
|
||||||
planAndExecute(target, callback);
|
planAndExecute(target, callback);
|
||||||
@ -60,11 +56,9 @@ void MoveConnection::setSpeedMultiplier(const double speed){
|
|||||||
|
|
||||||
void MoveConnection::stop() {
|
void MoveConnection::stop() {
|
||||||
std::cout<<"Stopping MoveConnection"<<std::endl;
|
std::cout<<"Stopping MoveConnection"<<std::endl;
|
||||||
cancelled = true;
|
while (rclcpp::ok() && state!=IDLE){
|
||||||
if(rclcpp::ok()){
|
|
||||||
moveGroup.stop();
|
moveGroup.stop();
|
||||||
while (lastTarget != nullptr) {}
|
usleep(1000);
|
||||||
}
|
}
|
||||||
cancelled = false;
|
|
||||||
std::cout<<"Stopped MoveConnection"<<std::endl;
|
std::cout<<"Stopped MoveConnection"<<std::endl;
|
||||||
}
|
}
|
||||||
|
|||||||
@ -12,10 +12,10 @@
|
|||||||
|
|
||||||
class MoveConnection {
|
class MoveConnection {
|
||||||
private:
|
private:
|
||||||
|
enum {IDLE,RUNNING,SPEED_CHANGE} state;
|
||||||
moveit::planning_interface::MoveGroupInterface moveGroup;
|
moveit::planning_interface::MoveGroupInterface moveGroup;
|
||||||
std::shared_ptr<geometry_msgs::msg::Pose> lastTarget = nullptr;
|
std::shared_ptr<geometry_msgs::msg::Pose> lastTarget = nullptr;
|
||||||
std::function<void(bool)> lastCallback = [](bool finished) {};
|
std::function<void(bool)> lastCallback = [](__attribute__((unused))bool finished) {};
|
||||||
bool cancelled=false;
|
|
||||||
double currentSpeed = 1;
|
double currentSpeed = 1;
|
||||||
std::mutex lock;
|
std::mutex lock;
|
||||||
public:
|
public:
|
||||||
|
|||||||
@ -11,6 +11,7 @@ BT::RobotMove::RobotMove(const std::string &name, const BT::NodeConfiguration &c
|
|||||||
}
|
}
|
||||||
|
|
||||||
BT::NodeStatus BT::RobotMove::onStart() {
|
BT::NodeStatus BT::RobotMove::onStart() {
|
||||||
|
std::cout << "Starting RobotMove" << std::endl;
|
||||||
std::shared_ptr<geometry_msgs::msg::Pose> pose;
|
std::shared_ptr<geometry_msgs::msg::Pose> pose;
|
||||||
if(!getInput<std::shared_ptr<geometry_msgs::msg::Pose>>("target",pose)){
|
if(!getInput<std::shared_ptr<geometry_msgs::msg::Pose>>("target",pose)){
|
||||||
std::cout << "no target available." << std::endl;
|
std::cout << "no target available." << std::endl;
|
||||||
@ -38,8 +39,9 @@ BT::NodeStatus BT::RobotMove::onRunning() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void BT::RobotMove::onHalted() {
|
void BT::RobotMove::onHalted() {
|
||||||
|
std::cout << "Halting RobotMove" << std::endl;
|
||||||
connection->get()->stop();
|
connection->get()->stop();
|
||||||
asyncResult=NodeStatus::IDLE;
|
asyncResult=NodeStatus::FAILURE;
|
||||||
}
|
}
|
||||||
|
|
||||||
BT::PortsList BT::RobotMove::providedPorts() {
|
BT::PortsList BT::RobotMove::providedPorts() {
|
||||||
|
|||||||
@ -80,7 +80,7 @@ int main(int argc, char **argv) {
|
|||||||
FeedbackMessage currentFeedback;
|
FeedbackMessage currentFeedback;
|
||||||
ActionMessage currentAction;
|
ActionMessage currentAction;
|
||||||
|
|
||||||
std::thread([feedbackQueue, ¤tAnimationGoalPtr, ¤tMovementGoalPtr, ¤tFeedback, ¤tAction] {
|
std::thread([feedbackQueue, ¤tAnimationGoalPtr, ¤tMovementGoalPtr, ¤tFeedback] {
|
||||||
while (true) {
|
while (true) {
|
||||||
FeedbackMessage newFeedback;
|
FeedbackMessage newFeedback;
|
||||||
if(mq_receive(feedbackQueue, (char *)&newFeedback, sizeof(ros_actor_message_queue_msgs::FeedbackMessage), nullptr)==-1){
|
if(mq_receive(feedbackQueue, (char *)&newFeedback, sizeof(ros_actor_message_queue_msgs::FeedbackMessage), nullptr)==-1){
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user