mirror of
https://github.com/westonrobot/ugv_sdk
synced 2023-04-08 06:32:14 +08:00
saved work
This commit is contained in:
11
demo/CMakeLists.txt
Executable file
11
demo/CMakeLists.txt
Executable file
@@ -0,0 +1,11 @@
|
||||
# demo
|
||||
add_subdirectory(scout_demo)
|
||||
|
||||
# add_executable(app_hunter_demo hunter_demo/hunter_demo.cpp)
|
||||
# target_link_libraries(app_hunter_demo ugv_sdk)
|
||||
|
||||
# add_executable(app_tracer_demo tracer_demo/tracer_demo.cpp)
|
||||
# target_link_libraries(app_tracer_demo ugv_sdk)
|
||||
|
||||
# add_executable(app_ranger_demo ranger_demo/ranger_demo.cpp)
|
||||
# target_link_libraries(app_ranger_demo ugv_sdk)
|
||||
92
demo/hunter_demo/hunter_demo.cpp
Normal file
92
demo/hunter_demo/hunter_demo.cpp
Normal file
@@ -0,0 +1,92 @@
|
||||
/*
|
||||
* demo_hunter_can.cpp
|
||||
*
|
||||
* Created on: Jun 12, 2019 05:03
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||
*/
|
||||
|
||||
#include "ugv_sdk/hunter_base.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
std::string device_name;
|
||||
int32_t baud_rate = 0;
|
||||
|
||||
if (argc == 2)
|
||||
{
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Specified CAN: " << device_name << std::endl;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "Usage: app_hunter_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_hunter_demo can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
HunterBase hunter;
|
||||
hunter.Connect(device_name);
|
||||
|
||||
int count = 0;
|
||||
while (true)
|
||||
{
|
||||
// motion control
|
||||
if (count < 5)
|
||||
{
|
||||
std::cout << "Motor: 0.2, 0.0" << std::endl;
|
||||
hunter.SetMotionCommand(0.2, 0.0);
|
||||
}
|
||||
else if (count < 10)
|
||||
{
|
||||
std::cout << "Motor: 0.8, 0.3" << std::endl;
|
||||
hunter.SetMotionCommand(0.8, 0.3);
|
||||
}
|
||||
else if (count < 15)
|
||||
{
|
||||
std::cout << "Motor: 1.5, 0.5" << std::endl;
|
||||
hunter.SetMotionCommand(1.5, 0.5);
|
||||
}
|
||||
else if (count < 20)
|
||||
{
|
||||
std::cout << "Motor: 1.0, 0.3" << std::endl;
|
||||
hunter.SetMotionCommand(1.0, 0.3);
|
||||
}
|
||||
else if (count < 25)
|
||||
{
|
||||
std::cout << "Motor: 0.0, 0.0" << std::endl;
|
||||
hunter.SetMotionCommand(0.0, 0.0);
|
||||
}
|
||||
else if (count < 30)
|
||||
{
|
||||
std::cout << "Motor: -0.5, -0.3" << std::endl;
|
||||
hunter.SetMotionCommand(-0.5, -0.3);
|
||||
}
|
||||
else if (count < 35)
|
||||
{
|
||||
std::cout << "Motor: -1.0, -0.5" << std::endl;
|
||||
hunter.SetMotionCommand(-1.0, -0.5);
|
||||
}
|
||||
else if (count < 40)
|
||||
{
|
||||
std::cout << "Motor: 0.0, 0.0," << std::endl;
|
||||
hunter.SetMotionCommand(0.0, 0.0);
|
||||
}
|
||||
|
||||
auto state = hunter.GetHunterState();
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
std::cout << "count: " << count << std::endl;
|
||||
std::cout << "control mode: " << static_cast<int>(state.control_mode) << " , base state: " << static_cast<int>(state.base_state) << std::endl;
|
||||
std::cout << "battery voltage: " << state.battery_voltage << std::endl;
|
||||
std::cout << "velocity (linear, angular): " << state.linear_velocity << ", " << state.steering_angle << std::endl;
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
sleep(1);
|
||||
++count;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
57
demo/ranger_demo/ranger_demo.cpp
Normal file
57
demo/ranger_demo/ranger_demo.cpp
Normal file
@@ -0,0 +1,57 @@
|
||||
/**
|
||||
* @Kit : Qt-Creator: Desktop
|
||||
* @Author : Wang Zhe
|
||||
* @Date : 2021-04-19 19:41:52
|
||||
* @FileName : ranger_demo.cpp
|
||||
* @Mail : wangzheqie@qq.com
|
||||
* Copyright : AgileX Robotics
|
||||
**/
|
||||
|
||||
#include "ugv_sdk/protocol_v2/ranger_base.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
std::string device_name;
|
||||
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Specified CAN: " << device_name << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: app_ranger_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_ranger_demo can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
RangerBase ranger;
|
||||
ranger.Connect(device_name);
|
||||
|
||||
ranger.EnableCommandedMode();
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
if (count < 100) {
|
||||
std::cout << "Motor: 0.2, 0" << std::endl;
|
||||
ranger.SetMotionCommand(0.2, 0.0);
|
||||
}
|
||||
|
||||
auto state = ranger.GetRangerState();
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
std::cout << "count: " << count << std::endl;
|
||||
std::cout << "control mode: "
|
||||
<< static_cast<int>(state.system_state.control_mode)
|
||||
<< " , vehicle state: "
|
||||
<< static_cast<int>(state.system_state.vehicle_state)
|
||||
<< std::endl;
|
||||
std::cout << "battery voltage: " << state.system_state.battery_voltage
|
||||
<< std::endl;
|
||||
std::cout << "velocity (linear, angular): "
|
||||
<< state.motion_state.linear_velocity << ", "
|
||||
<< state.motion_state.angular_velocity << std::endl;
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
usleep(20000);
|
||||
++count;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
6
demo/scout_demo/CMakeLists.txt
Executable file
6
demo/scout_demo/CMakeLists.txt
Executable file
@@ -0,0 +1,6 @@
|
||||
# tests
|
||||
add_executable(demo_scout_v2 scout_v2_demo.cpp)
|
||||
target_link_libraries(demo_scout_v2 ugv_sdk)
|
||||
|
||||
# add_executable(demo_scout_robot scout_robot_demo.cpp)
|
||||
# target_link_libraries(demo_scout_robot ugv_sdk)
|
||||
78
demo/scout_demo/scout_robot_demo.cpp
Normal file
78
demo/scout_demo/scout_robot_demo.cpp
Normal file
@@ -0,0 +1,78 @@
|
||||
/*
|
||||
* scout_robot_demo.cpp
|
||||
*
|
||||
* Created on: Jul 08, 2021 11:12
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2021 Weston Robot Pte. Ltd.
|
||||
*/
|
||||
|
||||
#include <iostream>
|
||||
|
||||
#include "ugv_sdk/mobile_base/scout_robot.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
std::string device_name;
|
||||
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Specified CAN: " << device_name << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: app_scout_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_scout_demo can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
ScoutRobot scout(AgilexProtocol::V1);
|
||||
// scout.Connect(device_name);
|
||||
|
||||
// scout.EnableCommandedMode();
|
||||
|
||||
// // // light control
|
||||
// std::cout << "Light: const off" << std::endl;
|
||||
// scout.SetLightCommand({CONST_OFF, 0, CONST_OFF, 0});
|
||||
// sleep(3);
|
||||
// std::cout << "Light: const on" << std::endl;
|
||||
// scout.SetLightCommand({CONST_ON, 0, CONST_ON, 0});
|
||||
// sleep(3);
|
||||
// std::cout << "Light: breath" << std::endl;
|
||||
// scout.SetLightCommand({BREATH, 0, BREATH, 0});
|
||||
// sleep(3);
|
||||
// std::cout << "Light: custom 90-80" << std::endl;
|
||||
// scout.SetLightCommand({CUSTOM, 90, CUSTOM, 80});
|
||||
// sleep(3);
|
||||
// std::cout << "Light: diabled cmd control" << std::endl;
|
||||
// scout.DisableLightControl();
|
||||
|
||||
// int count = 0;
|
||||
// while (true) {
|
||||
// // motion control
|
||||
// if (count < 100) {
|
||||
// std::cout << "Motor: 0.2, 0" << std::endl;
|
||||
// scout.SetMotionCommand(0.2, 0.0);
|
||||
// }
|
||||
|
||||
// // get robot state
|
||||
// auto state = scout.GetScoutState();
|
||||
// std::cout << "-------------------------------" << std::endl;
|
||||
// std::cout << "count: " << count << std::endl;
|
||||
// std::cout << "control mode: "
|
||||
// << static_cast<int>(state.system_state.control_mode)
|
||||
// << " , vehicle state: "
|
||||
// << static_cast<int>(state.system_state.vehicle_state)
|
||||
// << std::endl;
|
||||
// std::cout << "battery voltage: " << state.system_state.battery_voltage
|
||||
// << std::endl;
|
||||
// std::cout << "velocity (linear, angular): "
|
||||
// << state.motion_state.linear_velocity << ", "
|
||||
// << state.motion_state.angular_velocity << std::endl;
|
||||
// std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
// usleep(20000);
|
||||
// ++count;
|
||||
// }
|
||||
|
||||
return 0;
|
||||
}
|
||||
75
demo/scout_demo/scout_v2_demo.cpp
Normal file
75
demo/scout_demo/scout_v2_demo.cpp
Normal file
@@ -0,0 +1,75 @@
|
||||
/*
|
||||
* demo_scout_can.cpp
|
||||
*
|
||||
* Created on: Jun 12, 2019 05:03
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||
*/
|
||||
|
||||
#include "ugv_sdk/protocol_v2/scout_base_v2.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
std::string device_name;
|
||||
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Specified CAN: " << device_name << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: app_scout_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_scout_demo can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
ScoutBase scout;
|
||||
scout.Connect(device_name);
|
||||
|
||||
scout.EnableCommandedMode();
|
||||
|
||||
// // light control
|
||||
std::cout << "Light: const off" << std::endl;
|
||||
scout.SetLightCommand(CONST_OFF, 0, CONST_OFF, 0);
|
||||
sleep(3);
|
||||
std::cout << "Light: const on" << std::endl;
|
||||
scout.SetLightCommand(CONST_ON, 0, CONST_ON, 0);
|
||||
sleep(3);
|
||||
std::cout << "Light: breath" << std::endl;
|
||||
scout.SetLightCommand(BREATH, 0, BREATH, 0);
|
||||
sleep(3);
|
||||
std::cout << "Light: custom 90-80" << std::endl;
|
||||
scout.SetLightCommand(CUSTOM, 90, CUSTOM, 80);
|
||||
sleep(3);
|
||||
std::cout << "Light: diabled cmd control" << std::endl;
|
||||
scout.DisableLightControl();
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
// motion control
|
||||
if (count < 500) {
|
||||
std::cout << "Motor: 0.2, 0" << std::endl;
|
||||
scout.SetMotionCommand(0.2, 0.0);
|
||||
}
|
||||
|
||||
auto state = scout.GetRobotState();
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
std::cout << "count: " << count << std::endl;
|
||||
std::cout << "control mode: "
|
||||
<< static_cast<int>(state.system_state.control_mode)
|
||||
<< " , vehicle state: "
|
||||
<< static_cast<int>(state.system_state.vehicle_state)
|
||||
<< std::endl;
|
||||
std::cout << "battery voltage: " << state.system_state.battery_voltage
|
||||
<< std::endl;
|
||||
std::cout << "velocity (linear, angular): "
|
||||
<< state.motion_state.linear_velocity << ", "
|
||||
<< state.motion_state.angular_velocity << std::endl;
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
usleep(20000);
|
||||
++count;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
99
demo/tracer_demo/tracer_demo.cpp
Normal file
99
demo/tracer_demo/tracer_demo.cpp
Normal file
@@ -0,0 +1,99 @@
|
||||
/*
|
||||
* demo_tracer_can.cpp
|
||||
*
|
||||
* Created on: Jun 12, 2019 05:03
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||
*/
|
||||
|
||||
#include "ugv_sdk/protocol_v2/tracer_base.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
std::string device_name;
|
||||
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Specified CAN: " << device_name << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: app_tracer_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_tracer_demo can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
TracerBase tracer;
|
||||
tracer.Connect(device_name);
|
||||
|
||||
tracer.EnableCommandedMode();
|
||||
// tracer.DisableTimeout();
|
||||
|
||||
// light control
|
||||
std::cout << "Light: const off" << std::endl;
|
||||
tracer.SetLightCommand({CONST_OFF, 0});
|
||||
// usleep(50000);
|
||||
sleep(3);
|
||||
std::cout << "Light: const on" << std::endl;
|
||||
tracer.SetLightCommand({CONST_ON, 0});
|
||||
// usleep(50000);
|
||||
sleep(3);
|
||||
std::cout << "Light: breath" << std::endl;
|
||||
tracer.SetLightCommand({BREATH, 0});
|
||||
// usleep(50000);
|
||||
sleep(8);
|
||||
std::cout << "Light: custom 90-80" << std::endl;
|
||||
tracer.SetLightCommand({CUSTOM, 90});
|
||||
// usleep(50000);
|
||||
sleep(3);
|
||||
std::cout << "Light: diabled cmd control" << std::endl;
|
||||
tracer.SetLightCommand(TracerLightCmd());
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
// motion control
|
||||
if (count < 5) {
|
||||
std::cout << "Motor: 0.2, 0.0" << std::endl;
|
||||
tracer.SetMotionCommand(0.2, 0.0);
|
||||
} else if (count < 10) {
|
||||
std::cout << "Motor: 0.8, 0.3" << std::endl;
|
||||
tracer.SetMotionCommand(0.8, 0.3);
|
||||
} else if (count < 15) {
|
||||
std::cout << "Motor: 1.5, 0.5" << std::endl;
|
||||
tracer.SetMotionCommand(1.5, 0.5);
|
||||
} else if (count < 20) {
|
||||
std::cout << "Motor: 1.0, 0.3" << std::endl;
|
||||
tracer.SetMotionCommand(1.0, 0.3);
|
||||
} else if (count < 25) {
|
||||
std::cout << "Motor: 0.0, 0.0" << std::endl;
|
||||
tracer.SetMotionCommand(0.0, 0.0);
|
||||
} else if (count < 30) {
|
||||
std::cout << "Motor: -0.5, -0.3" << std::endl;
|
||||
tracer.SetMotionCommand(-0.5, -0.3);
|
||||
} else if (count < 35) {
|
||||
std::cout << "Motor: -1.0, -0.5" << std::endl;
|
||||
tracer.SetMotionCommand(-1.0, -0.5);
|
||||
} else if (count < 40) {
|
||||
std::cout << "Motor: 0.0, 0.0," << std::endl;
|
||||
tracer.SetMotionCommand(0.0, 0.0);
|
||||
}
|
||||
// tracer.SetMotionCommand(0.8, 0.8);
|
||||
|
||||
auto state = tracer.GetTracerState();
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
std::cout << "count: " << count << std::endl;
|
||||
std::cout << "control mode: " << static_cast<int>(state.system_state.control_mode)
|
||||
<< " , vehicle state: " << static_cast<int>(state.system_state.vehicle_state)
|
||||
<< std::endl;
|
||||
std::cout << "battery voltage: " << state.system_state.battery_voltage << std::endl;
|
||||
std::cout << "velocity (linear, angular): " << state.motion_state.linear_velocity << ", "
|
||||
<< state.motion_state.angular_velocity << std::endl;
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
// usleep(20000);
|
||||
sleep(1);
|
||||
++count;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
Reference in New Issue
Block a user