Compare commits
7 commits
Author | SHA1 | Date | |
---|---|---|---|
|
36d4379ddc | ||
|
c593059fb1 | ||
|
ed04957d94 | ||
|
27962d16a7 | ||
|
9c40daae88 | ||
|
de112d98e4 | ||
|
fa4cc1a0ad |
12 changed files with 579 additions and 1 deletions
|
@ -1,7 +1,11 @@
|
|||
# compLIB
|
||||
|
||||
Rewrite for ROS is the live packaged version since 18.07.2023.
|
||||
|
||||
# Dependencies
|
||||
|
||||
TODO: document
|
||||
|
||||
## Building documentation
|
||||
```
|
||||
pip install sphinx-rtd-theme
|
||||
|
|
55
compLib/CMakeLists.txt
Normal file
55
compLib/CMakeLists.txt
Normal file
|
@ -0,0 +1,55 @@
|
|||
cmake_minimum_required(VERSION 3.26)
|
||||
project(comp_lib)
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
find_package(rclcpp REQUIRED)
|
||||
find_package(rclcpp_action REQUIRED)
|
||||
find_package(std_msgs REQUIRED)
|
||||
find_package(irobot_create_msgs REQUIRED)
|
||||
find_package(geometry_msgs REQUIRED)
|
||||
|
||||
# add_executable(talker src/publisher_member_function.cpp)
|
||||
# ament_target_dependencies(talker rclcpp std_msgs irobot_create_msgs)
|
||||
|
||||
# add_executable(listener src/subscriber_member_function.cpp)
|
||||
# ament_target_dependencies(listener rclcpp std_msgs irobot_create_msgs)
|
||||
|
||||
# add_executable(drive src/drive_action.cpp)
|
||||
# ament_target_dependencies(drive rclcpp rclcpp_action std_msgs irobot_create_msgs)
|
||||
|
||||
# add_executable(set_vel src/set_speed.cpp)
|
||||
# ament_target_dependencies(set_vel rclcpp rclcpp_action std_msgs irobot_create_msgs geometry_msgs)
|
||||
|
||||
add_executable(compLib_node src/main.cpp src/motor.cpp src/controls.cpp)
|
||||
ament_target_dependencies(compLib_node rclcpp rclcpp_action std_msgs irobot_create_msgs geometry_msgs)
|
||||
|
||||
target_include_directories(compLib_node PRIVATE include)
|
||||
|
||||
install(TARGETS
|
||||
#talker
|
||||
#listener
|
||||
#drive
|
||||
#set_vel
|
||||
compLib_node
|
||||
DESTINATION lib/${PROJECT_NAME})
|
||||
# uncomment the following section in order to fill in
|
||||
# further dependencies manually.
|
||||
# find_package(<dependency> REQUIRED)
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
# the following line skips the linter which checks for copyrights
|
||||
# uncomment the line when a copyright and license is not present in all source files
|
||||
#set(ament_cmake_copyright_FOUND TRUE)
|
||||
# the following line skips cpplint (only works in a git repo)
|
||||
# uncomment the line when this package is not in a git repo
|
||||
#set(ament_cmake_cpplint_FOUND TRUE)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
ament_package()
|
14
compLib/include/comp_lib_node.h
Normal file
14
compLib/include/comp_lib_node.h
Normal file
|
@ -0,0 +1,14 @@
|
|||
#ifndef ROS_NODE_H
|
||||
#define ROS_NODE_H
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
class CompLibNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
CompLibNode();
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif
|
24
compLib/include/controls.h
Normal file
24
compLib/include/controls.h
Normal file
|
@ -0,0 +1,24 @@
|
|||
#ifndef CONTROLS_H
|
||||
#define CONTROLS_H
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp_action/rclcpp_action.hpp"
|
||||
|
||||
#include "irobot_create_msgs/msg/interface_buttons.hpp"
|
||||
#include "irobot_create_msgs/msg/lightring_leds.hpp"
|
||||
|
||||
class ButtonPressNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
ButtonPressNode();
|
||||
void bt1_wait();
|
||||
void bt2_wait();
|
||||
void kill();
|
||||
private:
|
||||
void result_callback(const irobot_create_msgs::msg::InterfaceButtons::SharedPtr result);
|
||||
rclcpp::Subscription<irobot_create_msgs::msg::InterfaceButtons>::SharedPtr interface_buttons_subscriber_;
|
||||
bool button1{false};
|
||||
bool button2{false};
|
||||
};
|
||||
|
||||
#endif
|
67
compLib/include/motor.h
Normal file
67
compLib/include/motor.h
Normal file
|
@ -0,0 +1,67 @@
|
|||
#ifndef MOTOR_H
|
||||
#define MOTOR_H
|
||||
|
||||
#include <thread>
|
||||
#include <memory>
|
||||
|
||||
#include <geometry_msgs/msg/twist.hpp>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp_action/rclcpp_action.hpp"
|
||||
|
||||
#include "irobot_create_msgs/action/drive_distance.hpp"
|
||||
#include "irobot_create_msgs/action/drive_arc.hpp"
|
||||
#include "irobot_create_msgs/action/rotate_angle.hpp"
|
||||
|
||||
class DriveDistNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
DriveDistNode();
|
||||
void drive_dist(float meters, float velocity);
|
||||
void kill();
|
||||
private:
|
||||
void result_callback(const rclcpp_action::ClientGoalHandle<irobot_create_msgs::action::DriveDistance>::WrappedResult & result);
|
||||
rclcpp_action::Client<irobot_create_msgs::action::DriveDistance>::SharedPtr drive_dist_action_;
|
||||
bool processing;
|
||||
};
|
||||
|
||||
class SetSpeedNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
SetSpeedNode();
|
||||
void drive(float speed);
|
||||
void stop();
|
||||
void kill();
|
||||
private:
|
||||
void set_speed(float speed);
|
||||
void drive_loop(float speed);
|
||||
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr speed_publisher_;
|
||||
bool run = true;
|
||||
std::thread t;
|
||||
};
|
||||
|
||||
class RotateAngleNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
RotateAngleNode();
|
||||
void rotate_angle(float angle, float velocity);
|
||||
void kill();
|
||||
private:
|
||||
void result_callback(const rclcpp_action::ClientGoalHandle<irobot_create_msgs::action::RotateAngle>::WrappedResult & result);
|
||||
rclcpp_action::Client<irobot_create_msgs::action::RotateAngle>::SharedPtr rotate_angle_action_;
|
||||
bool processing;
|
||||
};
|
||||
|
||||
class DriveArcNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
DriveArcNode();
|
||||
void drive_arc(float angle, float radius, float velocity, int direction=1);
|
||||
void kill();
|
||||
private:
|
||||
void result_callback(const rclcpp_action::ClientGoalHandle<irobot_create_msgs::action::DriveArc>::WrappedResult & result);
|
||||
rclcpp_action::Client<irobot_create_msgs::action::DriveArc>::SharedPtr drive_arc_action_;
|
||||
bool processing;
|
||||
};
|
||||
|
||||
#endif
|
11
compLib/include/sequence_lock.h
Normal file
11
compLib/include/sequence_lock.h
Normal file
|
@ -0,0 +1,11 @@
|
|||
#ifndef SEQUENCE_LOCK_H
|
||||
#define SEQUENCE_LOCK_H
|
||||
|
||||
#include <mutex>
|
||||
|
||||
namespace SequenceLock
|
||||
{
|
||||
std::mutex m;
|
||||
}
|
||||
|
||||
#endif
|
22
compLib/package.xml
Normal file
22
compLib/package.xml
Normal file
|
@ -0,0 +1,22 @@
|
|||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>comp_lib</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="matthias@todo.todo">matthias</maintainer>
|
||||
<license>TODO: License declaration</license>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
<depend>rclcpp</depend>
|
||||
<depend>rclcpp_action</depend>
|
||||
<depend>std_msgs</depend>
|
||||
<depend>irobot_create_msgs</depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
10
compLib/src/comp_lib_node.cpp
Normal file
10
compLib/src/comp_lib_node.cpp
Normal file
|
@ -0,0 +1,10 @@
|
|||
#include "ros_node.h"
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp_action/rclcpp_action.hpp"
|
||||
|
||||
CompLibNode::CompLibNode()
|
||||
: Node("CompLibNode")
|
||||
{
|
||||
|
||||
}
|
53
compLib/src/controls.cpp
Normal file
53
compLib/src/controls.cpp
Normal file
|
@ -0,0 +1,53 @@
|
|||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp_action/rclcpp_action.hpp"
|
||||
|
||||
#include "irobot_create_msgs/msg/interface_buttons.hpp"
|
||||
|
||||
#include "controls.h"
|
||||
|
||||
ButtonPressNode::ButtonPressNode()
|
||||
: Node("button_press_node")
|
||||
{
|
||||
interface_buttons_subscriber_ = this->create_subscription<irobot_create_msgs::msg::InterfaceButtons>(
|
||||
"/interface_buttons",
|
||||
rclcpp::SensorDataQoS(),
|
||||
std::bind(&ButtonPressNode::result_callback, this, std::placeholders::_1)
|
||||
);
|
||||
}
|
||||
|
||||
void ButtonPressNode::bt1_wait()
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "Wait for button 1...");
|
||||
button1 = false;
|
||||
while (!button1) {}
|
||||
button1 = false;
|
||||
}
|
||||
|
||||
void ButtonPressNode::bt2_wait()
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "Wait for button 2...");
|
||||
button2 = false;
|
||||
while (!button2) {}
|
||||
button2 = false;
|
||||
}
|
||||
|
||||
void ButtonPressNode::result_callback(const irobot_create_msgs::msg::InterfaceButtons::SharedPtr result)
|
||||
{
|
||||
if (result->button_1.is_pressed) {
|
||||
button1 = true;
|
||||
}
|
||||
|
||||
if (result->button_2.is_pressed) {
|
||||
button2 = true;
|
||||
}
|
||||
|
||||
if (result->button_power.is_pressed) {
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void ButtonPressNode::kill()
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "ButtonPressNode killed");
|
||||
rclcpp::shutdown();
|
||||
}
|
93
compLib/src/main.cpp
Normal file
93
compLib/src/main.cpp
Normal file
|
@ -0,0 +1,93 @@
|
|||
#include <thread>
|
||||
#include <memory>
|
||||
#include <chrono>
|
||||
#include <mutex>
|
||||
|
||||
#include "motor.h"
|
||||
#include "controls.h"
|
||||
|
||||
std::mutex action_mutex;
|
||||
|
||||
// #lazyness
|
||||
void run_node(std::shared_ptr<DriveDistNode> node)
|
||||
{
|
||||
rclcpp::spin(node);
|
||||
}
|
||||
|
||||
void run_node1(std::shared_ptr<SetSpeedNode> node)
|
||||
{
|
||||
rclcpp::spin(node);
|
||||
}
|
||||
|
||||
void run_node2(std::shared_ptr<RotateAngleNode> node)
|
||||
{
|
||||
rclcpp::spin(node);
|
||||
}
|
||||
|
||||
void run_node3(std::shared_ptr<DriveArcNode> node)
|
||||
{
|
||||
rclcpp::spin(node);
|
||||
}
|
||||
|
||||
void run_node4(std::shared_ptr<ButtonPressNode> node)
|
||||
{
|
||||
rclcpp::spin(node);
|
||||
}
|
||||
|
||||
int main(int argc, char * argv[])
|
||||
{
|
||||
rclcpp::init(argc, argv);
|
||||
|
||||
auto ddn = std::make_shared<DriveDistNode>();
|
||||
auto ssn = std::make_shared<SetSpeedNode>();
|
||||
auto ran = std::make_shared<RotateAngleNode>();
|
||||
auto dan = std::make_shared<DriveArcNode>();
|
||||
auto bpn = std::make_shared<ButtonPressNode>();
|
||||
|
||||
std::thread t;
|
||||
std::thread t1;
|
||||
std::thread t2;
|
||||
std::thread t3;
|
||||
std::thread t4;
|
||||
|
||||
t = std::thread(run_node, ddn);
|
||||
t1 = std::thread(run_node1, ssn);
|
||||
t2 = std::thread(run_node2, ran);
|
||||
t3 = std::thread(run_node3, dan);
|
||||
t4 = std::thread(run_node4, bpn);
|
||||
|
||||
bpn->bt1_wait();
|
||||
bpn->bt2_wait();
|
||||
bpn->bt1_wait();
|
||||
|
||||
ssn->drive(0.3);
|
||||
|
||||
std::this_thread::sleep_for (std::chrono::milliseconds(2000));
|
||||
|
||||
ssn->stop();
|
||||
|
||||
// std::this_thread::sleep_for (std::chrono::milliseconds(1000));
|
||||
|
||||
ran->rotate_angle(-45, 0.5);
|
||||
// std::this_thread::sleep_for (std::chrono::milliseconds(5000));
|
||||
|
||||
ddn->drive_dist(0.2, 0.3);
|
||||
|
||||
// std::this_thread::sleep_for (std::chrono::milliseconds(5000));
|
||||
|
||||
dan->drive_arc(90, 0.5, 0.5);
|
||||
|
||||
ddn->kill();
|
||||
ssn->kill();
|
||||
ddn->kill();
|
||||
dan->kill();
|
||||
bpn->kill();
|
||||
|
||||
t.join();
|
||||
t1.join();
|
||||
t2.join();
|
||||
t3.join();
|
||||
t4.join();
|
||||
|
||||
return 0;
|
||||
}
|
225
compLib/src/motor.cpp
Normal file
225
compLib/src/motor.cpp
Normal file
|
@ -0,0 +1,225 @@
|
|||
#include <chrono>
|
||||
#include <thread>
|
||||
#include <mutex>
|
||||
#include <future>
|
||||
#include <memory>
|
||||
|
||||
#include <geometry_msgs/msg/twist.hpp>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp_action/rclcpp_action.hpp"
|
||||
|
||||
#include "irobot_create_msgs/action/drive_distance.hpp"
|
||||
#include "irobot_create_msgs/action/drive_arc.hpp"
|
||||
#include "irobot_create_msgs/action/rotate_angle.hpp"
|
||||
|
||||
#include "motor.h"
|
||||
#include "sequence_lock.h"
|
||||
|
||||
double pi = 2 * acos(0.0);
|
||||
|
||||
DriveDistNode::DriveDistNode()
|
||||
: Node("drive_dist_node")
|
||||
{
|
||||
drive_dist_action_ = rclcpp_action::create_client<irobot_create_msgs::action::DriveDistance>(
|
||||
this,
|
||||
"/drive_distance"
|
||||
);
|
||||
}
|
||||
|
||||
void DriveDistNode::drive_dist(float meters, float velocity)
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "drive dist");
|
||||
processing = true;
|
||||
auto data = irobot_create_msgs::action::DriveDistance::Goal();
|
||||
auto send_goal_options = rclcpp_action::Client<irobot_create_msgs::action::DriveDistance>::SendGoalOptions();
|
||||
send_goal_options.result_callback =
|
||||
std::bind(&DriveDistNode::result_callback, this, std::placeholders::_1);
|
||||
|
||||
data.distance = meters;
|
||||
data.max_translation_speed = velocity;
|
||||
drive_dist_action_->async_send_goal(data, send_goal_options);
|
||||
|
||||
while (processing) {}
|
||||
}
|
||||
|
||||
void DriveDistNode::result_callback(const rclcpp_action::ClientGoalHandle<irobot_create_msgs::action::DriveDistance>::WrappedResult & result)
|
||||
{
|
||||
processing = false;
|
||||
switch (result.code) {
|
||||
case rclcpp_action::ResultCode::SUCCEEDED:
|
||||
RCLCPP_INFO(this->get_logger(), "finished dist");
|
||||
return;
|
||||
case rclcpp_action::ResultCode::ABORTED:
|
||||
RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
|
||||
return;
|
||||
case rclcpp_action::ResultCode::CANCELED:
|
||||
RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
|
||||
return;
|
||||
default:
|
||||
RCLCPP_ERROR(this->get_logger(), "Unknown result code");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void DriveDistNode::kill()
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "DriveDistNode killed");
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
|
||||
SetSpeedNode::SetSpeedNode()
|
||||
: Node("set_speed_node")
|
||||
{
|
||||
speed_publisher_ = this->create_publisher<geometry_msgs::msg::Twist>(
|
||||
"/cmd_vel",
|
||||
rclcpp::SensorDataQoS()
|
||||
);
|
||||
}
|
||||
|
||||
void SetSpeedNode::drive_loop(float speed)
|
||||
{
|
||||
while (run)
|
||||
{
|
||||
set_speed(speed);
|
||||
// sleep set as described at http://wiki.ros.org/Robots/TIAGo/Tutorials/motions/cmd_vel
|
||||
std::this_thread::sleep_for (std::chrono::milliseconds(333));
|
||||
}
|
||||
}
|
||||
|
||||
void SetSpeedNode::set_speed(float speed)
|
||||
{
|
||||
auto data = geometry_msgs::msg::Twist();
|
||||
|
||||
data.linear.x = speed;
|
||||
data.linear.y = 0;
|
||||
data.linear.z = 0;
|
||||
data.angular.x = 0;
|
||||
data.angular.x = 0;
|
||||
data.angular.x = 0;
|
||||
speed_publisher_->publish(data);
|
||||
}
|
||||
|
||||
void SetSpeedNode::drive(float speed)
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "Start drive");
|
||||
run = true;
|
||||
t = std::thread(&SetSpeedNode::drive_loop, this, speed);
|
||||
}
|
||||
|
||||
void SetSpeedNode::stop()
|
||||
{
|
||||
run = false;
|
||||
RCLCPP_INFO(this->get_logger(), "Stop drive");
|
||||
}
|
||||
|
||||
void SetSpeedNode::kill()
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "SetSpeedNode killed");
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
|
||||
RotateAngleNode::RotateAngleNode()
|
||||
: Node("rotate_angle_node")
|
||||
{
|
||||
rotate_angle_action_ = rclcpp_action::create_client<irobot_create_msgs::action::RotateAngle>(
|
||||
this,
|
||||
"rotate_angle"
|
||||
);
|
||||
}
|
||||
|
||||
void RotateAngleNode::rotate_angle(float angle, float velocity)
|
||||
{
|
||||
processing = true;
|
||||
angle *= pi / 180;
|
||||
auto data = irobot_create_msgs::action::RotateAngle::Goal();
|
||||
auto send_goal_options = rclcpp_action::Client<irobot_create_msgs::action::RotateAngle>::SendGoalOptions();
|
||||
send_goal_options.result_callback =
|
||||
std::bind(&RotateAngleNode::result_callback, this, std::placeholders::_1);
|
||||
|
||||
|
||||
data.angle = angle;
|
||||
data.max_rotation_speed = velocity;
|
||||
rotate_angle_action_->async_send_goal(data, send_goal_options);
|
||||
|
||||
while (processing) {}
|
||||
}
|
||||
|
||||
void RotateAngleNode::result_callback(const rclcpp_action::ClientGoalHandle<irobot_create_msgs::action::RotateAngle>::WrappedResult & result)
|
||||
{
|
||||
processing = false;
|
||||
switch (result.code) {
|
||||
case rclcpp_action::ResultCode::SUCCEEDED:
|
||||
RCLCPP_INFO(this->get_logger(), "finished rotation");
|
||||
return;
|
||||
case rclcpp_action::ResultCode::ABORTED:
|
||||
RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
|
||||
return;
|
||||
case rclcpp_action::ResultCode::CANCELED:
|
||||
RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
|
||||
return;
|
||||
default:
|
||||
RCLCPP_ERROR(this->get_logger(), "Unknown result code");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void RotateAngleNode::kill()
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "RotateAngleNode killed");
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
|
||||
DriveArcNode::DriveArcNode()
|
||||
: Node("drive_arc_node")
|
||||
{
|
||||
drive_arc_action_ = rclcpp_action::create_client<irobot_create_msgs::action::DriveArc>(
|
||||
this,
|
||||
"/drive_arc"
|
||||
);
|
||||
}
|
||||
|
||||
|
||||
void DriveArcNode::drive_arc(float angle, float radius, float velocity, int direction)
|
||||
{
|
||||
processing = true;
|
||||
angle *= pi / 180;
|
||||
auto data = irobot_create_msgs::action::DriveArc::Goal();
|
||||
auto send_goal_options = rclcpp_action::Client<irobot_create_msgs::action::DriveArc>::SendGoalOptions();
|
||||
send_goal_options.result_callback =
|
||||
std::bind(&DriveArcNode::result_callback, this, std::placeholders::_1);
|
||||
|
||||
|
||||
data.angle = angle;
|
||||
data.radius = radius;
|
||||
data.translate_direction = direction;
|
||||
data.max_translation_speed = velocity;
|
||||
drive_arc_action_->async_send_goal(data, send_goal_options);
|
||||
|
||||
while (processing) {}
|
||||
}
|
||||
|
||||
void DriveArcNode::result_callback(const rclcpp_action::ClientGoalHandle<irobot_create_msgs::action::DriveArc>::WrappedResult & result)
|
||||
{
|
||||
processing = false;
|
||||
switch (result.code) {
|
||||
case rclcpp_action::ResultCode::SUCCEEDED:
|
||||
RCLCPP_INFO(this->get_logger(), "finished arc");
|
||||
return;
|
||||
case rclcpp_action::ResultCode::ABORTED:
|
||||
RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
|
||||
return;
|
||||
case rclcpp_action::ResultCode::CANCELED:
|
||||
RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
|
||||
return;
|
||||
default:
|
||||
RCLCPP_ERROR(this->get_logger(), "Unknown result code");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void DriveArcNode::kill()
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "DriveArcNode killed");
|
||||
rclcpp::shutdown();
|
||||
}
|
|
@ -1,6 +1,6 @@
|
|||
#!/usr/bin/env bash
|
||||
|
||||
if [ $(uname -m) == "x86_64" ]; then
|
||||
if [ "$(uname -m)" = "x86_64" ]; then
|
||||
echo "Not running on RPi - Skipping postinstall"
|
||||
exit 0
|
||||
fi
|
||||
|
|
Reference in a new issue