diff --git a/src/lite6_controller/src/lite6_trajectory_executor.cpp b/src/lite6_controller/src/lite6_trajectory_executor.cpp new file mode 100644 index 0000000..4ba8a93 --- /dev/null +++ b/src/lite6_controller/src/lite6_trajectory_executor.cpp @@ -0,0 +1,111 @@ +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +//#include +//#include +//#include +#include +#include + +#include +#include + +#include +#include +#include +#include + + +#include +#include +#include +#include +#include +#include + + +#include +#include + +#include + +#include + +const std::string MOVE_GROUP = "lite6"; + +using namespace std::chrono_literals; + +class TrajectoryExecutor : public rclcpp::Node +{ + public: + //trajectory_pub = this->create_publisher("lite6_trajectory", 10); + rclcpp::Subscription::SharedPtr subscription; + moveit::planning_interface::MoveGroupInterface move_group; + + rclcpp::TimerBase::SharedPtr trajectory_timer_; + std::queue trajectory_queue; + bool busy = false; + + TrajectoryExecutor(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()) + : Node("lite6_trajectory_executor",options), + move_group(std::shared_ptr(std::move(this)), MOVE_GROUP) + { + subscription = this->create_subscription( + "lite6_trajectory", 100, std::bind(&TrajectoryExecutor::trajectory_callback, this, std::placeholders::_1)); + + trajectory_timer_ = this->create_wall_timer( + 10ms, std::bind(&TrajectoryExecutor::executeTrajectoryFromQueue, this)); + } + void trajectory_callback(const moveit_msgs::msg::RobotTrajectory msg) + { + RCLCPP_INFO(this->get_logger(), "Received trajectory, adding to queue"); + //move_group.execute(msg); + trajectory_queue.push(msg); + } + + void executeTrajectoryFromQueue() + { + if (busy || trajectory_queue.empty()) + return; + busy = true; + RCLCPP_INFO(this->get_logger(), "Executing next trajectory from queue"); + move_group.execute(trajectory_queue.front()); + trajectory_queue.pop(); + busy = false; + RCLCPP_INFO(this->get_logger(), "Finished executing trajectory"); + } +}; + +/** + * Starts lite6_controller + */ +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + + auto trajectory_executor = std::make_shared(); + + // TODO remove sleep if not necessary + // Sleep in case move_group not loaded + rclcpp::sleep_for(2s); + + //rclcpp::executors::SingleThreadedExecutor executor; + rclcpp::executors::MultiThreadedExecutor executor; + //executor.add_node(lite6); + executor.add_node(trajectory_executor); + executor.spin(); + + rclcpp::shutdown(); + return EXIT_SUCCESS; +}