|
|
@ -1,21 +1,92 @@ |
|
|
|
#include <functional> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#include <rclcpp/rclcpp.hpp> |
|
|
|
#include <rclcpp/rclcpp.hpp> |
|
|
|
#include <rclcpp/timer.hpp> |
|
|
|
#include <rclcpp/timer.hpp> |
|
|
|
#include <std_msgs/msg/string.hpp> |
|
|
|
#include <std_msgs/msg/string.hpp> |
|
|
|
#include <uaspire_msgs/msg/command.hpp> |
|
|
|
#include <uaspire_msgs/msg/command.hpp> |
|
|
|
#include <uaspire_msgs/msg/sensors.hpp> |
|
|
|
#include <uaspire_msgs/msg/sensors.hpp> |
|
|
|
|
|
|
|
#include <uaspire_msgs/msg/servo_positions.hpp> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef BUILD_RASPBERRY_PI |
|
|
|
|
|
|
|
#include <pigpiod_if2.h> |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
namespace arg = std::placeholders; |
|
|
|
namespace arg = std::placeholders; |
|
|
|
namespace ros = ::rclcpp; |
|
|
|
namespace ros = ::rclcpp; |
|
|
|
using UaspireCommand = ::uaspire_msgs::msg::Command; |
|
|
|
using UaspireCommand = ::uaspire_msgs::msg::Command; |
|
|
|
using UaspireSensors = ::uaspire_msgs::msg::Sensors; |
|
|
|
using UaspireSensors = ::uaspire_msgs::msg::Sensors; |
|
|
|
|
|
|
|
using UaspireServoPositions = ::uaspire_msgs::msg::ServoPositions; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
struct Servo { |
|
|
|
|
|
|
|
unsigned int pin; |
|
|
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
class IoNode : public ros::Node { |
|
|
|
|
|
|
|
private: |
|
|
|
|
|
|
|
ros::Subscription<UaspireServoPositions>::SharedPtr _servo_positions_subscription; |
|
|
|
|
|
|
|
std::array<Servo, 2> _servos; |
|
|
|
|
|
|
|
int _pi; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
public: |
|
|
|
|
|
|
|
RCLCPP_SHARED_PTR_DEFINITIONS(IoNode) |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
IoNode() : Node("uaspire_io") { |
|
|
|
|
|
|
|
#ifdef BUILD_RASPBERRY_PI |
|
|
|
|
|
|
|
// use default address and port
|
|
|
|
|
|
|
|
_pi = pigpio_start(NULL, NULL); |
|
|
|
|
|
|
|
if (_pi < 0) { |
|
|
|
|
|
|
|
RCLCPP_ERROR(get_logger(), "Error initializing pigpiod_if: %d", _pi); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
_servo_positions_subscription = create_subscription<UaspireServoPositions>( |
|
|
|
|
|
|
|
"uaspire/servo_positions", ros::QoS(10), |
|
|
|
|
|
|
|
std::bind(&IoNode::on_servo_positions, this, arg::_1)); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
init_servos(); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
~IoNode() { |
|
|
|
|
|
|
|
#ifdef BUILD_RASPBERRY_PI |
|
|
|
|
|
|
|
pigpio_stop(_pi); |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void init_servos() { |
|
|
|
|
|
|
|
_servos = { Servo { 9 }, Servo { 25 } }; |
|
|
|
|
|
|
|
for (auto& servo : _servos) { |
|
|
|
|
|
|
|
#ifdef BUILD_RASPBERRY_PI |
|
|
|
|
|
|
|
set_mode(_pi, servo.pin, PI_OUTPUT); |
|
|
|
|
|
|
|
gpio_write(_pi, servo.pin, PI_LOW); |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void on_servo_positions(UaspireServoPositions::SharedPtr msg) { |
|
|
|
|
|
|
|
std::array<float, 2> values = {msg->yaw, msg->pitch}; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
for (size_t i = 0; i < _servos.size(); ++i) { |
|
|
|
|
|
|
|
Servo& servo = _servos[i]; |
|
|
|
|
|
|
|
float value = values[i]; |
|
|
|
|
|
|
|
value = std::min(value, 90.f); |
|
|
|
|
|
|
|
value = std::max(value, -90.f); |
|
|
|
|
|
|
|
// convert value from -90 to 90 to int from 1000 to 2000 (us)
|
|
|
|
|
|
|
|
unsigned int decoded_value = static_cast<unsigned int>( |
|
|
|
|
|
|
|
((value / 90.f) * 500.f) + 1000); |
|
|
|
|
|
|
|
#ifdef BUILD_RASPBERRY_PI |
|
|
|
|
|
|
|
set_servo_pulsewidth(_pi, servo.pin, decoded_value); |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
class ControlsNode : public ros::Node { |
|
|
|
class ControlsNode : public ros::Node { |
|
|
|
private: |
|
|
|
private: |
|
|
|
ros::Subscription<UaspireCommand>::SharedPtr _command_subscription; |
|
|
|
ros::Subscription<UaspireCommand>::SharedPtr _command_subscription; |
|
|
|
ros::Publisher<UaspireSensors>::SharedPtr _sensors_publisher; |
|
|
|
ros::Publisher<UaspireSensors>::SharedPtr _sensors_publisher; |
|
|
|
|
|
|
|
ros::Publisher<UaspireServoPositions>::SharedPtr _servo_publisher; |
|
|
|
ros::TimerBase::SharedPtr _timer; |
|
|
|
ros::TimerBase::SharedPtr _timer; |
|
|
|
|
|
|
|
ros::TimerBase::SharedPtr _servo_timer; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
int _last_value; |
|
|
|
|
|
|
|
|
|
|
|
public: |
|
|
|
public: |
|
|
|
RCLCPP_SHARED_PTR_DEFINITIONS(ControlsNode) |
|
|
|
RCLCPP_SHARED_PTR_DEFINITIONS(ControlsNode) |
|
|
@ -26,10 +97,18 @@ public: |
|
|
|
std::bind(&ControlsNode::on_message, this, arg::_1)); |
|
|
|
std::bind(&ControlsNode::on_message, this, arg::_1)); |
|
|
|
_sensors_publisher = |
|
|
|
_sensors_publisher = |
|
|
|
create_publisher<UaspireSensors>("uaspire/sensors", ros::QoS(10)); |
|
|
|
create_publisher<UaspireSensors>("uaspire/sensors", ros::QoS(10)); |
|
|
|
|
|
|
|
_servo_publisher = |
|
|
|
|
|
|
|
create_publisher<UaspireServoPositions>("uaspire/servo_positions", ros::QoS(10)); |
|
|
|
_timer = create_wall_timer(std::chrono::milliseconds(1000), |
|
|
|
_timer = create_wall_timer(std::chrono::milliseconds(1000), |
|
|
|
std::bind(&ControlsNode::on_loop, this)); |
|
|
|
std::bind(&ControlsNode::on_loop, this)); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
_last_value = 0; |
|
|
|
|
|
|
|
// start 100Hz servo timer
|
|
|
|
|
|
|
|
_servo_timer = create_wall_timer(std::chrono::milliseconds(10), |
|
|
|
|
|
|
|
std::bind(&ControlsNode::on_servo_update, this)); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void on_message(const UaspireCommand::SharedPtr cmd) { |
|
|
|
void on_message(const UaspireCommand::SharedPtr cmd) { |
|
|
|
RCLCPP_INFO(get_logger(), "Command received: %s", cmd->data.c_str()); |
|
|
|
RCLCPP_INFO(get_logger(), "Command received: %s", cmd->data.c_str()); |
|
|
|
} |
|
|
|
} |
|
|
@ -40,13 +119,25 @@ public: |
|
|
|
_sensors_publisher->publish(sensors); |
|
|
|
_sensors_publisher->publish(sensors); |
|
|
|
RCLCPP_INFO(get_logger(), "loop"); |
|
|
|
RCLCPP_INFO(get_logger(), "loop"); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void on_servo_update() { |
|
|
|
|
|
|
|
UaspireServoPositions positions; |
|
|
|
|
|
|
|
positions.pitch = _last_value - 90; |
|
|
|
|
|
|
|
positions.yaw = 90 - _last_value; |
|
|
|
|
|
|
|
_servo_publisher->publish(positions); |
|
|
|
|
|
|
|
_last_value = (_last_value + 10) % 180; |
|
|
|
|
|
|
|
} |
|
|
|
}; |
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
int main(int argc, char **argv) { |
|
|
|
int main(int argc, char **argv) { |
|
|
|
ros::init(argc, argv); |
|
|
|
ros::init(argc, argv); |
|
|
|
{ |
|
|
|
{ |
|
|
|
auto node = ControlsNode::make_shared(); |
|
|
|
ros::executors::MultiThreadedExecutor executor; |
|
|
|
ros::spin(node); |
|
|
|
auto io_node = IoNode::make_shared(); |
|
|
|
|
|
|
|
auto controls_node = ControlsNode::make_shared(); |
|
|
|
|
|
|
|
executor.add_node(io_node); |
|
|
|
|
|
|
|
executor.add_node(controls_node); |
|
|
|
|
|
|
|
executor.spin(); |
|
|
|
} |
|
|
|
} |
|
|
|
ros::shutdown(); |
|
|
|
ros::shutdown(); |
|
|
|
return 0; |
|
|
|
return 0; |
|
|
|