mirror of
https://github.com/westonrobot/ugv_sdk
synced 2023-04-08 06:32:14 +08:00
demo: renamed demo folder to sample, updated readme
This commit is contained in:
8
sample/CMakeLists.txt
Executable file
8
sample/CMakeLists.txt
Executable file
@@ -0,0 +1,8 @@
|
||||
# demo
|
||||
add_subdirectory(scout_demo)
|
||||
add_subdirectory(tracer_demo)
|
||||
add_subdirectory(ranger_demo)
|
||||
add_subdirectory(bunker_demo)
|
||||
add_subdirectory(hunter_demo)
|
||||
|
||||
add_subdirectory(utils_demo)
|
||||
2
sample/bunker_demo/CMakeLists.txt
Executable file
2
sample/bunker_demo/CMakeLists.txt
Executable file
@@ -0,0 +1,2 @@
|
||||
add_executable(demo_bunker_robot bunker_robot_demo.cpp)
|
||||
target_link_libraries(demo_bunker_robot ugv_sdk)
|
||||
86
sample/bunker_demo/bunker_robot_demo.cpp
Normal file
86
sample/bunker_demo/bunker_robot_demo.cpp
Normal file
@@ -0,0 +1,86 @@
|
||||
/*
|
||||
* bunker_robot_demo.cpp
|
||||
*
|
||||
* Created on: Jul 08, 2021 11:12
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2021 Weston Robot Pte. Ltd.
|
||||
*/
|
||||
|
||||
#include <unistd.h>
|
||||
|
||||
#include <memory>
|
||||
#include <iostream>
|
||||
|
||||
#include "ugv_sdk/mobile_robot/bunker_robot.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
std::string protocol_version;
|
||||
std::string device_name;
|
||||
|
||||
if (argc == 3) {
|
||||
protocol_version = {argv[1]};
|
||||
device_name = {argv[2]};
|
||||
std::cout << "Use protocol " << protocol_version << " on interface "
|
||||
<< device_name << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: app_bunker_demo <protocol-version> <interface>"
|
||||
<< std::endl
|
||||
<< "Example 1: ./app_bunker_demo v1 can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
std::unique_ptr<BunkerRobot> bunker;
|
||||
if (protocol_version == "v1") {
|
||||
bunker =
|
||||
std::unique_ptr<BunkerRobot>(new BunkerRobot(ProtocolVersion::AGX_V1));
|
||||
} else if (protocol_version == "v2") {
|
||||
bunker =
|
||||
std::unique_ptr<BunkerRobot>(new BunkerRobot(ProtocolVersion::AGX_V2));
|
||||
} else {
|
||||
std::cout << "Error: invalid protocol version string" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (bunker == nullptr)
|
||||
std::cout << "Failed to create robot object" << std::endl;
|
||||
|
||||
bunker->Connect(device_name);
|
||||
|
||||
if (bunker->GetParserProtocolVersion() == ProtocolVersion::AGX_V2) {
|
||||
bunker->EnableCommandedMode();
|
||||
std::cout << "Protocol version 2" << std::endl;
|
||||
} else {
|
||||
std::cout << "Protocol version 1" << std::endl;
|
||||
}
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
// motion control
|
||||
std::cout << "Motor: 1.0, 0" << std::endl;
|
||||
bunker->SetMotionCommand(1.0, 0.0);
|
||||
|
||||
// get robot state
|
||||
auto state = bunker->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)
|
||||
<< " , error code: " << std::hex << state.system_state.error_code
|
||||
<< ", 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;
|
||||
}
|
||||
2
sample/hunter_demo/CMakeLists.txt
Executable file
2
sample/hunter_demo/CMakeLists.txt
Executable file
@@ -0,0 +1,2 @@
|
||||
add_executable(demo_hunter_robot hunter_robot_demo.cpp)
|
||||
target_link_libraries(demo_hunter_robot ugv_sdk)
|
||||
101
sample/hunter_demo/hunter_robot_demo.cpp
Normal file
101
sample/hunter_demo/hunter_robot_demo.cpp
Normal file
@@ -0,0 +1,101 @@
|
||||
/*
|
||||
* hunter_robot_demo.cpp
|
||||
*
|
||||
* Created on: Jul 08, 2021 11:12
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2021 Weston Robot Pte. Ltd.
|
||||
*/
|
||||
|
||||
#include <unistd.h>
|
||||
|
||||
#include <memory>
|
||||
#include <iostream>
|
||||
|
||||
#include "ugv_sdk/mobile_robot/hunter_robot.hpp"
|
||||
#include "ugv_sdk/utilities/protocol_detector.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
std::string device_name;
|
||||
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Selected interface " << device_name << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: app_hunter_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_hunter_demo can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
std::unique_ptr<HunterRobot> hunter;
|
||||
|
||||
ProtocolDetector detector;
|
||||
detector.Connect(device_name);
|
||||
auto proto = detector.DetectProtocolVersion(5);
|
||||
|
||||
if (proto == ProtocolVersion::AGX_V1) {
|
||||
hunter =
|
||||
std::unique_ptr<HunterRobot>(new HunterRobot(ProtocolVersion::AGX_V1));
|
||||
} else if (proto == ProtocolVersion::AGX_V2) {
|
||||
hunter =
|
||||
std::unique_ptr<HunterRobot>(new HunterRobot(ProtocolVersion::AGX_V2));
|
||||
} else {
|
||||
std::cout << "Detected protocol: UNKONWN" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (hunter == nullptr)
|
||||
std::cout << "Failed to create robot object" << std::endl;
|
||||
|
||||
hunter->Connect(device_name);
|
||||
|
||||
if (hunter->GetParserProtocolVersion() == ProtocolVersion::AGX_V2) {
|
||||
hunter->EnableCommandedMode();
|
||||
std::cout << "Protocol version 2" << std::endl;
|
||||
} else {
|
||||
std::cout << "Protocol version 1" << std::endl;
|
||||
}
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
// motion control
|
||||
std::cout << "Motor: 1.0, 0" << std::endl;
|
||||
// hunter->SetMotionCommand(1.0, 0.0);
|
||||
|
||||
// get robot state
|
||||
auto state = hunter->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)
|
||||
<< " , error code: " << std::hex << state.system_state.error_code
|
||||
<< ", battery voltage: " << state.system_state.battery_voltage
|
||||
<< std::endl;
|
||||
std::cout << "velocity (linear, angular): "
|
||||
<< state.motion_state.linear_velocity << ", "
|
||||
<< state.motion_state.steering_angle << std::endl;
|
||||
|
||||
auto actuator = hunter->GetActuatorState();
|
||||
if (hunter->GetParserProtocolVersion() == ProtocolVersion::AGX_V1) {
|
||||
for (int i = 0; i < 3; ++i) {
|
||||
printf("motor %d: current %f, rpm %d, driver temp %f, motor temp %f\n",
|
||||
actuator.actuator_state[i].motor_id,
|
||||
actuator.actuator_state[i].current,
|
||||
actuator.actuator_state[i].rpm,
|
||||
actuator.actuator_state[i].driver_temp,
|
||||
actuator.actuator_state[i].motor_temp);
|
||||
}
|
||||
} else {
|
||||
}
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
usleep(20000);
|
||||
++count;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
2
sample/ranger_demo/CMakeLists.txt
Normal file
2
sample/ranger_demo/CMakeLists.txt
Normal file
@@ -0,0 +1,2 @@
|
||||
add_executable(demo_ranger_robot ranger_robot_demo.cpp)
|
||||
target_link_libraries(demo_ranger_robot ugv_sdk)
|
||||
57
sample/ranger_demo/ranger_robot_demo.cpp
Normal file
57
sample/ranger_demo/ranger_robot_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/mobile_robot/ranger_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_ranger_demo <interface>" << std::endl
|
||||
<< "Example 1: ./app_ranger_demo can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
RangerRobot 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.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;
|
||||
}
|
||||
5
sample/scout_demo/CMakeLists.txt
Executable file
5
sample/scout_demo/CMakeLists.txt
Executable file
@@ -0,0 +1,5 @@
|
||||
add_executable(demo_scout_robot scout_robot_demo.cpp)
|
||||
target_link_libraries(demo_scout_robot ugv_sdk)
|
||||
|
||||
add_executable(demo_scout_mini_omni_robot scout_mini_omni_demo.cpp)
|
||||
target_link_libraries(demo_scout_mini_omni_robot ugv_sdk)
|
||||
140
sample/scout_demo/scout_mini_omni_demo.cpp
Normal file
140
sample/scout_demo/scout_mini_omni_demo.cpp
Normal file
@@ -0,0 +1,140 @@
|
||||
/*
|
||||
* scout_robot_demo.cpp
|
||||
*
|
||||
* Created on: Jul 08, 2021 11:12
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2021 Weston Robot Pte. Ltd.
|
||||
*/
|
||||
|
||||
#include <unistd.h>
|
||||
|
||||
#include <memory>
|
||||
#include <iostream>
|
||||
|
||||
#include "ugv_sdk/mobile_robot/scout_robot.hpp"
|
||||
#include "ugv_sdk/utilities/protocol_detector.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
std::string device_name;
|
||||
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Selected interface " << device_name << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: demo_scout_mini_omni_robot <interface>" << std::endl
|
||||
<< "Example 1: ./demo_scout_mini_omni_robot can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
std::unique_ptr<ScoutMiniOmniRobot> scout;
|
||||
|
||||
ProtocolDetector detector;
|
||||
detector.Connect(device_name);
|
||||
auto proto = detector.DetectProtocolVersion(5);
|
||||
if (proto == ProtocolVersion::AGX_V1) {
|
||||
std::cout << "Detected protocol: AGX_V1" << std::endl;
|
||||
scout = std::unique_ptr<ScoutMiniOmniRobot>(
|
||||
new ScoutMiniOmniRobot(ProtocolVersion::AGX_V1));
|
||||
|
||||
} else if (proto == ProtocolVersion::AGX_V2) {
|
||||
std::cout << "Detected protocol: AGX_V2" << std::endl;
|
||||
scout = std::unique_ptr<ScoutMiniOmniRobot>(
|
||||
new ScoutMiniOmniRobot(ProtocolVersion::AGX_V2));
|
||||
} else {
|
||||
std::cout << "Detected protocol: UNKONWN" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (scout == nullptr)
|
||||
std::cout << "Failed to create robot object" << std::endl;
|
||||
|
||||
scout->Connect(device_name);
|
||||
|
||||
if (scout->GetParserProtocolVersion() == ProtocolVersion::AGX_V2) {
|
||||
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 30-40" << std::endl;
|
||||
scout->SetLightCommand(CUSTOM, 30, CUSTOM, 40);
|
||||
sleep(3);
|
||||
scout->SetLightCommand(CONST_OFF, 0, CONST_OFF, 0);
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
// motion control
|
||||
std::cout << "Setting motion command: 0.0, 0,0, 0.8" << std::endl;
|
||||
scout->SetMotionCommand(0.0, 0.3, 0.0);
|
||||
|
||||
// get robot state
|
||||
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)
|
||||
<< " , error code: " << std::hex << state.system_state.error_code
|
||||
<< std::dec
|
||||
<< ", battery voltage: " << state.system_state.battery_voltage
|
||||
<< std::endl;
|
||||
std::cout << "velocity (linear, angular, lateral): "
|
||||
<< state.motion_state.linear_velocity << ", "
|
||||
<< state.motion_state.angular_velocity << ", "
|
||||
<< state.motion_state.lateral_velocity << std::endl;
|
||||
std::cout << "core state age (ms): "
|
||||
<< std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||
AgxMsgRefClock::now() - state.time_stamp)
|
||||
.count()
|
||||
<< std::endl;
|
||||
|
||||
auto actuator = scout->GetActuatorState();
|
||||
if (scout->GetParserProtocolVersion() == ProtocolVersion::AGX_V1) {
|
||||
for (int i = 0; i < 4; ++i) {
|
||||
printf("motor %d: current %f, rpm %d, driver temp %f, motor temp %f\n",
|
||||
actuator.actuator_state[i].motor_id,
|
||||
actuator.actuator_state[i].current,
|
||||
actuator.actuator_state[i].rpm,
|
||||
actuator.actuator_state[i].driver_temp,
|
||||
actuator.actuator_state[i].motor_temp);
|
||||
}
|
||||
std::cout << "actuator state age (ms): "
|
||||
<< std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||
AgxMsgRefClock::now() - actuator.time_stamp)
|
||||
.count()
|
||||
<< std::endl;
|
||||
} else {
|
||||
for (int i = 0; i < 4; ++i) {
|
||||
printf("motor %d: current %f, rpm %d, driver temp %f, motor temp %f\n",
|
||||
actuator.actuator_hs_state[i].motor_id,
|
||||
actuator.actuator_hs_state[i].current,
|
||||
actuator.actuator_hs_state[i].rpm,
|
||||
actuator.actuator_ls_state[i].driver_temp,
|
||||
actuator.actuator_ls_state[i].motor_temp);
|
||||
}
|
||||
std::cout << "actuator state age (ms): "
|
||||
<< std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||
AgxMsgRefClock::now() - actuator.time_stamp)
|
||||
.count()
|
||||
<< std::endl;
|
||||
}
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
usleep(20000);
|
||||
++count;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
159
sample/scout_demo/scout_robot_demo.cpp
Normal file
159
sample/scout_demo/scout_robot_demo.cpp
Normal file
@@ -0,0 +1,159 @@
|
||||
/*
|
||||
* scout_robot_demo.cpp
|
||||
*
|
||||
* Created on: Jul 08, 2021 11:12
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2021 Weston Robot Pte. Ltd.
|
||||
*/
|
||||
|
||||
#include <unistd.h>
|
||||
|
||||
#include <memory>
|
||||
#include <iostream>
|
||||
|
||||
#include "ugv_sdk/mobile_robot/scout_robot.hpp"
|
||||
#include "ugv_sdk/utilities/protocol_detector.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
std::string device_name;
|
||||
std::string robot_subtype;
|
||||
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Selected interface " << device_name << ", robot type: scout"
|
||||
<< std::endl;
|
||||
} else if (argc == 3) {
|
||||
robot_subtype = {argv[1]};
|
||||
device_name = {argv[2]};
|
||||
std::cout << "Selected interface " << device_name
|
||||
<< ", robot type: " << robot_subtype << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: demo_scout_robot [<robot-subtype>] <interface>"
|
||||
<< std::endl
|
||||
<< "Example 1: ./demo_scout_robot can0" << std::endl
|
||||
<< "\t <robot-subtype>: mini" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
bool is_scout_mini = false;
|
||||
if (robot_subtype == "mini") {
|
||||
is_scout_mini = true;
|
||||
} else if (!robot_subtype.empty() && robot_subtype != "scout") {
|
||||
std::cout
|
||||
<< "Unkonwn robot subtype. Supported subtypes: \"scout\" or \"mini\""
|
||||
<< std::endl;
|
||||
}
|
||||
|
||||
std::unique_ptr<ScoutRobot> scout;
|
||||
|
||||
ProtocolDetector detector;
|
||||
if (detector.Connect(device_name)) {
|
||||
auto proto = detector.DetectProtocolVersion(5);
|
||||
if (proto == ProtocolVersion::AGX_V1) {
|
||||
std::cout << "Detected protocol: AGX_V1" << std::endl;
|
||||
scout = std::unique_ptr<ScoutRobot>(
|
||||
new ScoutRobot(ProtocolVersion::AGX_V1, is_scout_mini));
|
||||
} else if (proto == ProtocolVersion::AGX_V2) {
|
||||
std::cout << "Detected protocol: AGX_V2" << std::endl;
|
||||
scout = std::unique_ptr<ScoutRobot>(
|
||||
new ScoutRobot(ProtocolVersion::AGX_V2, is_scout_mini));
|
||||
} else {
|
||||
std::cout << "Detected protocol: UNKONWN" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (scout == nullptr)
|
||||
std::cout << "Failed to create robot object" << std::endl;
|
||||
|
||||
scout->Connect(device_name);
|
||||
|
||||
if (scout->GetParserProtocolVersion() == ProtocolVersion::AGX_V2) {
|
||||
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 30-40" << std::endl;
|
||||
scout->SetLightCommand(CUSTOM, 30, CUSTOM, 40);
|
||||
sleep(3);
|
||||
scout->SetLightCommand(CONST_OFF, 0, CONST_OFF, 0);
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
// motion control
|
||||
std::cout << "Motor: 1.0, 0" << std::endl;
|
||||
scout->SetMotionCommand(1.0, 0.0);
|
||||
|
||||
// get robot state
|
||||
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)
|
||||
<< " , error code: " << std::hex << state.system_state.error_code
|
||||
<< std::dec
|
||||
<< ", 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 << "core state age (ms): "
|
||||
<< std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||
AgxMsgRefClock::now() - state.time_stamp)
|
||||
.count()
|
||||
<< std::endl;
|
||||
|
||||
auto actuator = scout->GetActuatorState();
|
||||
if (scout->GetParserProtocolVersion() == ProtocolVersion::AGX_V1) {
|
||||
for (int i = 0; i < 4; ++i) {
|
||||
printf("motor %d: current %f, rpm %d, driver temp %f, motor temp %f\n",
|
||||
actuator.actuator_state[i].motor_id,
|
||||
actuator.actuator_state[i].current,
|
||||
actuator.actuator_state[i].rpm,
|
||||
actuator.actuator_state[i].driver_temp,
|
||||
actuator.actuator_state[i].motor_temp);
|
||||
}
|
||||
std::cout << "actuator state age (ms): "
|
||||
<< std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||
AgxMsgRefClock::now() - actuator.time_stamp)
|
||||
.count()
|
||||
<< std::endl;
|
||||
} else {
|
||||
for (int i = 0; i < 4; ++i) {
|
||||
printf("motor %d: current %f, rpm %d, driver temp %f, motor temp %f\n",
|
||||
actuator.actuator_hs_state[i].motor_id,
|
||||
actuator.actuator_hs_state[i].current,
|
||||
actuator.actuator_hs_state[i].rpm,
|
||||
actuator.actuator_ls_state[i].driver_temp,
|
||||
actuator.actuator_ls_state[i].motor_temp);
|
||||
}
|
||||
std::cout << "actuator state age (ms): "
|
||||
<< std::chrono::duration_cast<std::chrono::milliseconds>(
|
||||
AgxMsgRefClock::now() - actuator.time_stamp)
|
||||
.count()
|
||||
<< std::endl;
|
||||
}
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
usleep(20000);
|
||||
++count;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
2
sample/tracer_demo/CMakeLists.txt
Normal file
2
sample/tracer_demo/CMakeLists.txt
Normal file
@@ -0,0 +1,2 @@
|
||||
add_executable(demo_tracer_robot tracer_robot_demo.cpp)
|
||||
target_link_libraries(demo_tracer_robot ugv_sdk)
|
||||
88
sample/tracer_demo/tracer_robot_demo.cpp
Normal file
88
sample/tracer_demo/tracer_robot_demo.cpp
Normal file
@@ -0,0 +1,88 @@
|
||||
/*
|
||||
* scout_robot_demo.cpp
|
||||
*
|
||||
* Created on: Jul 13, 2021 22:22
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2021 Weston Robot Pte. Ltd.
|
||||
*/
|
||||
|
||||
#include <unistd.h>
|
||||
|
||||
#include <memory>
|
||||
#include <iostream>
|
||||
|
||||
#include "ugv_sdk/mobile_robot/tracer_robot.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
std::string device_name;
|
||||
|
||||
if (argc == 2) {
|
||||
device_name = {argv[1]};
|
||||
std::cout << "Using interface "
|
||||
<< device_name << std::endl;
|
||||
} else {
|
||||
std::cout << "Usage: app_tracer_demo <interface>"
|
||||
<< std::endl
|
||||
<< "Example 1: ./app_tracer_demo can0" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
std::unique_ptr<TracerRobot> tracer;
|
||||
tracer = std::unique_ptr<TracerRobot>(new TracerRobot());
|
||||
if (tracer == nullptr)
|
||||
std::cout << "Failed to create robot object" << std::endl;
|
||||
|
||||
tracer->Connect(device_name);
|
||||
tracer->EnableCommandedMode();
|
||||
|
||||
// light control
|
||||
std::cout << "Light: const off" << std::endl;
|
||||
tracer->SetLightCommand(CONST_OFF, 0);
|
||||
sleep(3);
|
||||
std::cout << "Light: const on" << std::endl;
|
||||
tracer->SetLightCommand(CONST_ON, 0);
|
||||
sleep(3);
|
||||
std::cout << "Light: breath" << std::endl;
|
||||
tracer->SetLightCommand(BREATH, 0);
|
||||
sleep(3);
|
||||
std::cout << "Light: custom 30-80" << std::endl;
|
||||
tracer->SetLightCommand(CUSTOM, 30);
|
||||
sleep(3);
|
||||
// std::cout << "Light: diabled cmd control" << std::endl;
|
||||
// scout->DisableLightControl();
|
||||
tracer->SetLightCommand(CONST_OFF, 0);
|
||||
|
||||
int count = 0;
|
||||
while (true) {
|
||||
// motion control
|
||||
std::cout << "Motor: 1.0, 0" << std::endl;
|
||||
tracer->SetMotionCommand(1.0, 0.0);
|
||||
|
||||
// get robot state
|
||||
auto state = tracer->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)
|
||||
<< " , error code: " << std::hex << state.system_state.error_code
|
||||
<< ", 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;
|
||||
|
||||
for (int i = 0; i < 2; ++i) {
|
||||
}
|
||||
std::cout << "-------------------------------" << std::endl;
|
||||
|
||||
usleep(20000);
|
||||
++count;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
2
sample/utils_demo/CMakeLists.txt
Normal file
2
sample/utils_demo/CMakeLists.txt
Normal file
@@ -0,0 +1,2 @@
|
||||
add_executable(demo_protocol_detector demo_protocol_detector.cpp)
|
||||
target_link_libraries(demo_protocol_detector ugv_sdk)
|
||||
35
sample/utils_demo/demo_protocol_detector.cpp
Normal file
35
sample/utils_demo/demo_protocol_detector.cpp
Normal file
@@ -0,0 +1,35 @@
|
||||
/*
|
||||
* demo_protocol_detect.cpp
|
||||
*
|
||||
* Created on: Jul 15, 2021 14:10
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2021 Weston Robot Pte. Ltd.
|
||||
*/
|
||||
|
||||
#include <memory>
|
||||
#include <iostream>
|
||||
|
||||
#include "ugv_sdk/utilities/protocol_detector.hpp"
|
||||
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
ProtocolDetector detector;
|
||||
if (detector.Connect("can0")) {
|
||||
auto proto = detector.DetectProtocolVersion(5);
|
||||
|
||||
if (proto == ProtocolVersion::AGX_V1) {
|
||||
std::cout << "Detected protocol: AGX_V1" << std::endl;
|
||||
} else if (proto == ProtocolVersion::AGX_V2) {
|
||||
std::cout << "Detected protocol: AGX_V2" << std::endl;
|
||||
} else {
|
||||
std::cout << "Detected protocol: UNKONWN" << std::endl;
|
||||
}
|
||||
} else {
|
||||
std::cout << "Failed to open port" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
Reference in New Issue
Block a user