add px4 controller cmakelists
This commit is contained in:
@@ -22,9 +22,16 @@ find_package(px4_ros_com REQUIRED)
|
|||||||
find_package(px4_msgs REQUIRED)
|
find_package(px4_msgs REQUIRED)
|
||||||
|
|
||||||
add_executable(heartbeat src/heartbeat.cpp)
|
add_executable(heartbeat src/heartbeat.cpp)
|
||||||
|
add_executable(px4_controller src/px4_controller.cpp)
|
||||||
|
|
||||||
target_include_directories(heartbeat PUBLIC
|
target_include_directories(heartbeat PUBLIC
|
||||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
$<INSTALL_INTERFACE:include>)
|
$<INSTALL_INTERFACE:include>)
|
||||||
|
|
||||||
|
target_include_directories(px4_controller PUBLIC
|
||||||
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
|
$<INSTALL_INTERFACE:include>)
|
||||||
|
|
||||||
ament_target_dependencies(
|
ament_target_dependencies(
|
||||||
heartbeat
|
heartbeat
|
||||||
rclcpp
|
rclcpp
|
||||||
@@ -32,7 +39,7 @@ ament_target_dependencies(
|
|||||||
px4_msgs
|
px4_msgs
|
||||||
)
|
)
|
||||||
|
|
||||||
install(TARGETS heartbeat
|
install(TARGETS heartbeat px4_controller
|
||||||
DESTINATION lib/${PROJECT_NAME})
|
DESTINATION lib/${PROJECT_NAME})
|
||||||
|
|
||||||
if(BUILD_TESTING)
|
if(BUILD_TESTING)
|
||||||
|
|||||||
74
src/px4_connection/src/px4_controller.cpp
Normal file
74
src/px4_connection/src/px4_controller.cpp
Normal file
@@ -0,0 +1,74 @@
|
|||||||
|
/*
|
||||||
|
|
||||||
|
We need to send attitude setpoints to be able to arm the drone:
|
||||||
|
https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET
|
||||||
|
We need attitude setpoints because we don't have a GPS:
|
||||||
|
https://discuss.px4.io/t/cannot-arm-drone-with-companion-computer-arming-denied-manual-control-lost/31565/9
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <chrono>
|
||||||
|
|
||||||
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
|
||||||
|
#include <px4_msgs/msg/offboard_control_mode.hpp>
|
||||||
|
#include <px4_msgs/msg/timesync.hpp>
|
||||||
|
|
||||||
|
using namespace std::chrono_literals;
|
||||||
|
|
||||||
|
class HeartBeat : public rclcpp::Node
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
HeartBeat() : Node("setpoint_sender")
|
||||||
|
{
|
||||||
|
// create a publisher on the offboard control mode topic
|
||||||
|
offboard_control_mode_publisher_ = this->create_publisher<px4_msgs::msg::OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
|
||||||
|
// create timer to send heartbeat messages (offboard control) every 100ms
|
||||||
|
timer_ = this->create_wall_timer(100ms, std::bind(&HeartBeat::send_heartbeat, this));
|
||||||
|
start_time = this->get_clock()->now().seconds();
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Publish offboard control mode messages as a heartbeat.
|
||||||
|
* Only the attitude is enabled, because that is how the drone will be controlled.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void send_heartbeat()
|
||||||
|
{
|
||||||
|
// set message to enable attitude
|
||||||
|
auto msg = px4_msgs::msg::OffboardControlMode();
|
||||||
|
msg.position = false;
|
||||||
|
msg.velocity = false;
|
||||||
|
msg.acceleration = false;
|
||||||
|
msg.attitude = true;
|
||||||
|
msg.body_rate = false;
|
||||||
|
msg.actuator = false;
|
||||||
|
|
||||||
|
// get timestamp and publish message
|
||||||
|
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
|
||||||
|
offboard_control_mode_publisher_->publish(msg);
|
||||||
|
RCLCPP_INFO(this->get_logger(), "sent offboard control mode message!");
|
||||||
|
|
||||||
|
// check if 5 seconds have elapsed
|
||||||
|
if (this->get_clock()->now().seconds() - start_time > 5)
|
||||||
|
{
|
||||||
|
RCLCPP_INFO(this->get_logger(), "5 seconds elapsed!");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
rclcpp::Publisher<px4_msgs::msg::OffboardControlMode>::SharedPtr offboard_control_mode_publisher_;
|
||||||
|
rclcpp::TimerBase::SharedPtr timer_;
|
||||||
|
double start_time;
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
rclcpp::spin(std::make_shared<HeartBeat>());
|
||||||
|
rclcpp::shutdown();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user