Skip to content

Commit

Permalink
add ranger topic examples
Browse files Browse the repository at this point in the history
  • Loading branch information
wangzheqie committed Apr 26, 2021
1 parent cadbde5 commit 947d5c8
Show file tree
Hide file tree
Showing 5 changed files with 204 additions and 1 deletion.
91 changes: 90 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,96 @@ sudo apt install ros-$ROS_DISTRO-teleop-twist-keyboard
roslaunch ranger_bringup ranger_teleop_keyboard.launch
```

## Examples






----

## Ros Topic Examples

* Input: the car linear velocity and the heading angle
* Output: total linear velocity, x direction velocity, y direction velocity, angular velocity, central steer angle and rotate radius, .etc

### Publish topic to control the car

see `ranger_ros/ranger_examples/src/input.cpp` for details

```c++
////----------------control by ros topic---------------------------------
ros::Publisher motion_mode =
node.advertise<ranger_msgs::RangerSetting>("/ranger_setting", 1);
ranger_msgs::RangerSetting setting;
setting.motion_mode = ranger_msgs::RangerSetting::MOTION_MODE_ACKERMAN;
motion_mode.publish(setting);

////------------------move by ros topic --------------------------------
ros::Publisher move_cmd =
node.advertise<geometry_msgs::Twist>("/cmd_vel", 10);
geometry_msgs::Twist cmd;
cmd.linear.x = 0.1; // the motor will run at 0.1m/s
cmd.angular.z = 30.0 / 180.0 * M_PI; // the heading angle of the car

// publish robot state at 50Hz while listening to twist commands
ros::Rate rate(50);
while (ros::ok()) {
ros::spinOnce();

// /cmd_vel topic must send at 50Hz, even stop need send 0m/s
move_cmd.publish(cmd);

rate.sleep();
}
```
or publish by command line
```shell
rostopic pub -1 /cmd_vel geometry_msgs/Twist -- '[0.1, 0.0, 0.0]' '[0.0, 0.0, 0.52358]' # 0.52358 = 30 degree
```



### Subcribe the car output

see `ranger_ros/ranger_examples/src/output.cpp` for details

```c++
ros::Subscriber status_sub = node.subscribe<ranger_msgs::RangerStatus>(
"/ranger_status", 10, StatusCallback);
```

```c++
void StatusCallback(ranger_msgs::RangerStatus::ConstPtr msg) {
std::cout << "linear velocity: " << msg->linear_velocity << std::endl;
std::cout << "angular velocity: " << msg->angular_velocity << std::endl;
std::cout << "x direction linear velocity: " << msg->x_linear_vel << std::endl;
std::cout << "y direction linear linear velocity: " << msg->y_linear_vel << std::endl;
std::cout << "rotate radius: " << msg->motion_radius << std::endl;
std::cout << "car heading angle: " << msg->steering_angle << std::endl;
// ...etc
}
```
or show the data by rostopic
```shell
rostopic echo /ranger_status
```







----

## Sdk API Examples

### 0. enable can control

Expand Down
4 changes: 4 additions & 0 deletions ranger_examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,10 @@ add_executable(change_the_mode src/change_the_mode.cpp)
target_link_libraries(change_the_mode ${catkin_LIBRARIES})
add_executable(control_the_car src/control_the_car.cpp)
target_link_libraries(control_the_car ${catkin_LIBRARIES})
add_executable(input src/input.cpp)
target_link_libraries(input ${catkin_LIBRARIES})
add_executable(output src/output.cpp)
target_link_libraries(output ${catkin_LIBRARIES})

## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
Expand Down
1 change: 1 addition & 0 deletions ranger_examples/src/control_the_car.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ int main(int argc, char *argv[]) {
// publish robot state at 50Hz while listening to twist commands
ros::Rate rate(50);
while (ros::ok()) {
// send command in 50hz, nor will timeout
robot->SetMotionCommand(l_v, angle_z);
ros::spinOnce();
rate.sleep();
Expand Down
69 changes: 69 additions & 0 deletions ranger_examples/src/input.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
/**
* @Kit : Qt-Creator: Desktop
* @Author : Wang Zhe
* @Date : 2021-04-26 18:47:25
* @FileName : input.cpp
* @Mail : [email protected]
* Copyright : AgileX Robotics (2021)
**/

#include <memory>

#include <nav_msgs/Odometry.h>
#include <ros/ros.h>

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

using namespace westonrobot;

std::shared_ptr<RangerBase> robot;

int main(int argc, char *argv[]) {
// setup ROS node
ros::init(argc, argv, "input");
ros::NodeHandle node(""), private_node("~");

// instantiate a robot object
robot = std::make_shared<RangerBase>();

robot->Connect("can0");
robot->EnableCommandedMode();

////-----------------direct control by call the sdk function-------------
// 0 Arckmann 1 Slide 2 round, 3 Sloping
robot->SetMotionMode(0);
// robot->SetMotionMode(1);
// robot->SetMotionMode(2);
// robot->SetMotionMode(3);

// robot->SetMotionCommand(0.1, 30.0/180.0 * M_PI); // steer angle = 30°

////----------------control by ros topic---------------------------------
ros::Publisher motion_mode =
node.advertise<ranger_msgs::RangerSetting>("/ranger_setting", 1);
ranger_msgs::RangerSetting setting;
setting.motion_mode = ranger_msgs::RangerSetting::MOTION_MODE_ACKERMAN;
motion_mode.publish(setting);

////------------------move by ros topic --------------------------------
ros::Publisher move_cmd =
node.advertise<geometry_msgs::Twist>("/cmd_vel", 10);
geometry_msgs::Twist cmd;
cmd.linear.x = 0.1; // the motor will run at 0.1m/s
cmd.angular.z = 30.0 / 180.0 * M_PI; // the heading angle of the car

// publish robot state at 50Hz while listening to twist commands
ros::Rate rate(50);
while (ros::ok()) {
ros::spinOnce();

// /cmd_vel topic must send at 50Hz, even stop need send 0m/s
move_cmd.publish(cmd);

rate.sleep();
}
return 0;
}
40 changes: 40 additions & 0 deletions ranger_examples/src/output.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/**
* @Kit : Qt-Creator: Desktop
* @Author : Wang Zhe
* @Date : 2021-04-26 18:47:49
* @FileName : output.cpp
* @Mail : [email protected]
* Copyright : AgileX Robotics (2021)
**/

#include <ranger_msgs/RangerStatus.h>
#include <ros/ros.h>
#include <iostream>

void StatusCallback(ranger_msgs::RangerStatus::ConstPtr msg) {
std::cout << "linear velocity: " << msg->linear_velocity << std::endl;
std::cout << "angular velocity: " << msg->angular_velocity << std::endl;
std::cout << "x direction linear velocity: " << msg->x_linear_vel
<< std::endl;
std::cout << "y direction linear linear velocity: " << msg->y_linear_vel
<< std::endl;
std::cout << "rotate radius: " << msg->motion_radius << std::endl;
std::cout << "car heading angle: " << msg->steering_angle << std::endl;
// ...etc
}

int main(int argc, char *argv[]) {
// setup ROS node
ros::init(argc, argv, "output");
ros::NodeHandle node(""), private_node("~");

ros::Subscriber status_sub = node.subscribe<ranger_msgs::RangerStatus>(
"/ranger_status", 10, StatusCallback);

ros::Rate rate(50);
while (ros::ok()) {
ros::spinOnce();
rate.sleep();
}
return 0;
}

0 comments on commit 947d5c8

Please sign in to comment.