Skip to content

Commit

Permalink
add examples and readme
Browse files Browse the repository at this point in the history
  • Loading branch information
wangzheqie committed Apr 25, 2021
1 parent 267bd76 commit 462a4f0
Show file tree
Hide file tree
Showing 3 changed files with 77 additions and 8 deletions.
46 changes: 42 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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();
```


Expand All @@ -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);
```
Expand All @@ -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
}
```


Expand Down
2 changes: 2 additions & 0 deletions ranger_examples/src/change_the_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()) {
Expand Down
37 changes: 33 additions & 4 deletions ranger_examples/src/control_the_car.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,12 @@
#include <nav_msgs/Odometry.h>
#include <ros/ros.h>

#include <ranger_msgs/RangerSetting.h>
#include <ranger_msgs/RangerStatus.h>
#include "ranger_base/ranger_messenger.hpp"
#include "ugv_sdk/ranger_base.hpp"

using namespace ranger_msgs;
using namespace westonrobot;

void Ackermann();
Expand All @@ -23,6 +26,7 @@ void Round();
void Sloping();

std::shared_ptr<RangerBase> robot;
double l_v = 0.0, angle_z = 0.0;

int main(int argc, char *argv[]) {
// setup ROS node
Expand All @@ -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
}

0 comments on commit 462a4f0

Please sign in to comment.