From 462a4f0d5a43a2804f6bf210ec9b26a69a649a95 Mon Sep 17 00:00:00 2001 From: wangzheqie Date: Sun, 25 Apr 2021 13:20:13 +0800 Subject: [PATCH] add examples and readme --- README.md | 46 ++++++++++++++++++++++--- ranger_examples/src/change_the_mode.cpp | 2 ++ ranger_examples/src/control_the_car.cpp | 37 +++++++++++++++++--- 3 files changed, 77 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index ad7b2f3..6afba64 100644 --- a/README.md +++ b/README.md @@ -57,8 +57,8 @@ roslaunch ranger_bringup ranger_teleop_keyboard.launch ### 0. enable can control ```shell - robot->Connect("can0"); - robot->EnableCommandedMode(); +robot->Connect("can0"); +robot->EnableCommandedMode(); ``` @@ -68,7 +68,15 @@ roslaunch ranger_bringup ranger_teleop_keyboard.launch see `ranger_ros/ranger_examples/src/change_the_mode.cpp` for more details ```c++ - +robot->Connect("can0"); +robot->EnableCommandedMode(); + +// 0 Arckmann 1 Slide 2 round, 3 Sloping +// 0 前后阿克曼 1 横移 2 自旋 3 侧移 +robot->SetMotionMode(0); +// robot->SetMotionMode(1); +// robot->SetMotionMode(2); +// robot->SetMotionMode(3); ``` @@ -78,7 +86,37 @@ see `ranger_ros/ranger_examples/src/change_the_mode.cpp` for more details see `ranger_ros/ranger_examples/src/control_the_car.cpp` for more details ```c++ - +robot->SetMotionCommand(0.1, 30.0/180.0 * M_PI); // steer angle = 30° + +// or write them in a function +void Ackermann() { + robot->SetMotionMode(0); + // or + robot->SetMotionMode(RangerSetting::MOTION_MODE_ACKERMAN); + l_v = 0.1; // m/s + angle_z = 30 / 180 * M_PI; // rad +} +void Slide() { + robot->SetMotionMode(1); + // or + robot->SetMotionMode(RangerSetting::MOTION_MODE_SLIDE); + l_v = 0.1; // m/s + angle_z = 30 / 180 * M_PI; // rad +} +void Round() { + robot->SetMotionMode(2); + // or + robot->SetMotionMode(RangerSetting::MOTION_MODE_ROUND); + l_v = 0.1; + // angle_z is not used +} +void Sloping() { + robot->SetMotionMode(3); + // or + robot->SetMotionMode(RangerSetting::MOTION_MODE_SLOPING); + l_v = 0.1; + // angle_z is not used +} ``` diff --git a/ranger_examples/src/change_the_mode.cpp b/ranger_examples/src/change_the_mode.cpp index f1002fa..e70554b 100644 --- a/ranger_examples/src/change_the_mode.cpp +++ b/ranger_examples/src/change_the_mode.cpp @@ -36,6 +36,8 @@ int main(int argc, char *argv[]) { // robot->SetMotionMode(2); // robot->SetMotionMode(3); + robot->SetMotionCommand(0.1, 30.0/180.0 * M_PI); // steer angle = 30° + // publish robot state at 50Hz while listening to twist commands ros::Rate rate(50); while (ros::ok()) { diff --git a/ranger_examples/src/control_the_car.cpp b/ranger_examples/src/control_the_car.cpp index 22e7f2a..547a6fc 100644 --- a/ranger_examples/src/control_the_car.cpp +++ b/ranger_examples/src/control_the_car.cpp @@ -12,9 +12,12 @@ #include #include +#include +#include #include "ranger_base/ranger_messenger.hpp" #include "ugv_sdk/ranger_base.hpp" +using namespace ranger_msgs; using namespace westonrobot; void Ackermann(); @@ -23,6 +26,7 @@ void Round(); void Sloping(); std::shared_ptr robot; +double l_v = 0.0, angle_z = 0.0; int main(int argc, char *argv[]) { // setup ROS node @@ -43,12 +47,37 @@ int main(int argc, char *argv[]) { // publish robot state at 50Hz while listening to twist commands ros::Rate rate(50); while (ros::ok()) { + robot->SetMotionCommand(l_v, angle_z); ros::spinOnce(); rate.sleep(); } return 0; } -void Ackermann(){} -void Slide(){} -void Round(){} -void Sloping(){} +void Ackermann() { + robot->SetMotionMode(0); + // or + robot->SetMotionMode(RangerSetting::MOTION_MODE_ACKERMAN); + l_v = 0.1; // m/s + angle_z = 30 / 180 * M_PI; // rad +} +void Slide() { + robot->SetMotionMode(1); + // or + robot->SetMotionMode(RangerSetting::MOTION_MODE_SLIDE); + l_v = 0.1; // m/s + angle_z = 30 / 180 * M_PI; // rad +} +void Round() { + robot->SetMotionMode(2); + // or + robot->SetMotionMode(RangerSetting::MOTION_MODE_ROUND); + l_v = 0.1; + // angle_z is not used +} +void Sloping() { + robot->SetMotionMode(3); + // or + robot->SetMotionMode(RangerSetting::MOTION_MODE_SLOPING); + l_v = 0.1; + // angle_z is not used +}