change CMakeLists.txt of heartbeat to include packages for ros

This commit is contained in:
Sem van der Hoeven
2023-04-25 16:15:03 +02:00
parent 010559ea9b
commit 8b1790f763
6 changed files with 79 additions and 12 deletions

View File

@@ -18,6 +18,8 @@ endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(px4_ros_com REQUIRED)
find_package(px4_msgs REQUIRED)
add_executable(heartbeat src/heartbeat.cpp)
target_include_directories(heartbeat PUBLIC
@@ -25,7 +27,9 @@ target_include_directories(heartbeat PUBLIC
$<INSTALL_INTERFACE:include>)
ament_target_dependencies(
heartbeat
"rclcpp"
rclcpp
px4_ros_com
px4_msgs
)
install(TARGETS heartbeat

View File

@@ -3,9 +3,9 @@
<package format="3">
<name>px4_connection</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<description>Package to communicate with PX4 through the XRCE-DDS bridge</description>
<maintainer email="semmer99@gmail.com">ubuntu</maintainer>
<license>TODO: License declaration</license>
<license>Apache License 2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>

View File

@@ -1,10 +1,74 @@
#include <cstdio>
/*
int main(int argc, char ** argv)
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
{
(void) argc;
(void) argv;
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();
}
printf("hello world px4_connection package\n");
return 0;
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;
}

View File

@@ -12,7 +12,6 @@ https://discuss.px4.io/t/cannot-arm-drone-with-companion-computer-arming-denied-
#include "rclcpp/rclcpp.hpp"
#include <px4_msgs/msg/offboard_control_mode.hpp>
#include <px4_msgs/msg/vehicle_attitude_setpoint.hpp>
#include <px4_msgs/msg/timesync.hpp>
using namespace std::chrono_literals;