Add drive arc functionality

This commit is contained in:
Matthias Guzmits 2023-07-19 18:36:07 +02:00
parent de112d98e4
commit ed04957d94
3 changed files with 89 additions and 10 deletions

View file

@ -10,6 +10,7 @@
#include "rclcpp_action/rclcpp_action.hpp"
#include "irobot_create_msgs/action/drive_distance.hpp"
#include "irobot_create_msgs/action/drive_arc.hpp"
#include "irobot_create_msgs/action/rotate_angle.hpp"
class DriveDistNode : public rclcpp::Node
@ -51,4 +52,16 @@ private:
bool processing;
};
class DriveArcNode : public rclcpp::Node
{
public:
DriveArcNode();
void drive_arc(float angle, float radius, float velocity, int direction=1);
void kill();
private:
void result_callback(const rclcpp_action::ClientGoalHandle<irobot_create_msgs::action::DriveArc>::WrappedResult & result);
rclcpp_action::Client<irobot_create_msgs::action::DriveArc>::SharedPtr drive_arc_action_;
bool processing;
};
#endif