15 #include <spdlog/spdlog.h>
25 std::atomic<bool> g_stop_sched = {
false};
32 static unsigned int loop_counter = 0;
37 throw std::runtime_error(
38 "PeriodicTask: Fault occurred on the connected robot, exiting ...");
41 std::vector<double> target_vel(robot.
info().
DoF);
42 std::vector<double> target_acc(robot.
info().
DoF);
45 if (loop_counter == 5000) {
46 spdlog::warn(
">>>>> Adding simulated loop delay <<<<<");
49 else if (loop_counter > 5000) {
50 std::this_thread::sleep_for(std::chrono::microseconds(995));
55 }
catch (
const std::exception& e) {
56 spdlog::error(e.what());
64 std::cout <<
"Required arguments: [robot_sn]" << std::endl;
65 std::cout <<
" robot_sn: Serial number of the robot to connect. Remove any space, e.g. Rizon4s-123456" << std::endl;
66 std::cout <<
"Optional arguments: None" << std::endl;
67 std::cout << std::endl;
71 int main(
int argc,
char* argv[])
75 if (argc < 2 || flexiv::rdk::utility::ProgramArgsExistAny(argc, argv, {
"-h",
"--help"})) {
81 std::string robot_sn = argv[1];
91 spdlog::warn(
"Fault occurred on the connected robot, trying to clear ...");
94 spdlog::error(
"Fault cannot be cleared, exiting ...");
97 spdlog::info(
"Fault on the connected robot is cleared");
101 spdlog::info(
"Enabling robot ...");
106 std::this_thread::sleep_for(std::chrono::seconds(1));
108 spdlog::info(
"Robot is now operational");
111 robot.
SwitchMode(flexiv::rdk::Mode::RT_JOINT_POSITION);
114 auto init_pos = robot.
states().
q;
115 spdlog::info(
"Initial joint positions set to: {}", flexiv::rdk::utility::Vec2Str(init_pos));
116 spdlog::warn(
">>>>> Simulated loop delay will be added after 5 seconds <<<<<");
122 scheduler.
AddTask(std::bind(PeriodicTask, std::ref(robot), std::ref(init_pos)),
128 while (!g_stop_sched) {
129 std::this_thread::sleep_for(std::chrono::milliseconds(1));
134 }
catch (
const std::exception& e) {
135 spdlog::error(e.what());
Main interface with the robot, containing several function categories and background services.
const RobotStates states() const
[Non-blocking] Current states data of the robot.
const RobotInfo info() const
[Non-blocking] General information about the connected robot.
bool operational(bool verbose=true) const
[Non-blocking] Whether the robot is ready to be operated, which requires the following conditions to ...
void SwitchMode(Mode mode)
[Blocking] Switch to a new control mode and wait until mode transition is finished.
void StreamJointPosition(const std::vector< double > &positions, const std::vector< double > &velocities, const std::vector< double > &accelerations)
[Non-blocking] Continuously stream joint position, velocity, and acceleration command to the robot....
void Enable()
[Blocking] Enable the robot, if E-stop is released and there's no fault, the robot will release brake...
bool fault() const
[Non-blocking] Whether the robot is in fault state.
bool ClearFault(unsigned int timeout_sec=30)
[Blocking] Try to clear minor or critical fault of the robot without a power cycle.
Real-time scheduler that can simultaneously run multiple periodic tasks. Parameters for each task are...
int max_priority() const
[Non-blocking] Get maximum available priority for user tasks.
void AddTask(std::function< void(void)> &&callback, const std::string &task_name, int interval, int priority, int cpu_affinity=-1)
[Non-blocking] Add a new periodic task to the scheduler's task pool. Each task in the pool is assigne...
void Stop()
[Blocking] Stop all added tasks. The periodic execution will stop and all task threads will be closed...
void Start()
[Blocking] Start all added tasks. A dedicated thread will be created for each added task and the peri...