# PX4仿真實作
### 實作找尋設備
[DDS bridge](https://docs.px4.io/main/en/middleware/uxrce_dds.html)
[port setting](https://docs.px4.io/main/en/modules/modules_system.html#uxrce-dds-client)
### 找尋電腦裝置
```
ls /dev/ttyUSB*
```
**MicroAgent**
```
sudo MicroXRCEAgent serial --dev /dev/ttyUSB0 -b 57600 -v 6
uxrce_dds_client start -t serial -d /dev/ttyS1 -b 57600
uxrce_dds_client status
uxrce_dds_client stop
```
**Offboard command**
```
source /opt/ros/humble/setup.bash
colcon build
source install/local_setup.bash
ros2 run px4_ros_com offboard_control
```
```
MicroXRCEAgent udp4 -p 8888
```
為了使模擬數據可以更完整呈現,我們可以去做資料分析,首先需安裝pyulog:
[Pyulog](https://github.com/PX4/pyulog),此為安裝教學。
接著我們須確認模擬結果是否有紀錄。
```
make px4_sitl gazebo
```
進入gazebo模擬後,在Teminal輸入**logger status**確認飛行紀錄有沒有進行,若無
```
logger on
```
開始進行紀錄
## ulog2csv
當我們需要從仿真中獲取數據,並在matlab裡面進行分析,就需要進行一個轉檔的動作
```
~/.local/bin/ulog2csv your_log.ulg
```
## Offboard code
### attitude
```javascript=
/****************************************************************************
*
* Copyright 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
*
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its contributors
* may be used to endorse or promote products derived from this software without
* specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @brief Offboard control example
* @file offboard_control.cpp
* @addtogroup examples
* @author Mickey Cowden <info@cowden.tech>
* @author Nuno Marques <nuno.marques@dronesolutions.io>
*/
#include <px4_msgs/msg/offboard_control_mode.hpp>
#include <px4_msgs/msg/trajectory_setpoint.hpp>
#include <px4_msgs/msg/vehicle_command.hpp>
#include <px4_msgs/msg/vehicle_control_mode.hpp>
#include <px4_msgs/msg/vehicle_attitude_setpoint.hpp>
#include <rclcpp/rclcpp.hpp>
#include <stdint.h>
#include <chrono>
#include <iostream>
using namespace std::chrono;
using namespace std::chrono_literals;
using namespace px4_msgs::msg;
class OffboardControl : public rclcpp::Node
{
public:
OffboardControl() : Node("offboard_control")
{
offboard_control_mode_publisher_ = this->create_publisher<OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
trajectory_setpoint_publisher_ = this->create_publisher<TrajectorySetpoint>("/fmu/in/trajectory_setpoint", 10);
vehicle_command_publisher_ = this->create_publisher<VehicleCommand>("/fmu/in/vehicle_command", 10);
vehicle_attitude_setpoint_publisher_ = this->create_publisher<VehicleAttitudeSetpoint>("/fmu/in/vehicle_attitude_setpoint", 10);
offboard_setpoint_counter_ = 0;
auto timer_callback = [this]() -> void {
if (offboard_setpoint_counter_ == 10) {
// Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
}
// offboard_control_mode needs to be paired with trajectory_setpoint
publish_offboard_control_mode();
publish_trajectory_setpoint();
publish_vehicle_attitude_setpoint();
// stop the counter after reaching 11
if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
}
};
timer_ = this->create_wall_timer(100ms, timer_callback);
}
void arm();
void disarm();
private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<OffboardControlMode>::SharedPtr offboard_control_mode_publisher_;
rclcpp::Publisher<TrajectorySetpoint>::SharedPtr trajectory_setpoint_publisher_;
rclcpp::Publisher<VehicleCommand>::SharedPtr vehicle_command_publisher_;
rclcpp::Publisher<VehicleAttitudeSetpoint>::SharedPtr vehicle_attitude_setpoint_publisher_;
std::atomic<uint64_t> timestamp_; //!< common synced timestamped
std::array<float, 4> quat_from_euler(double roll, double pitch, double yaw);
uint64_t offboard_setpoint_counter_; //!< counter for the number of setpoints sent
float time_counter_ = 0.0;
void publish_offboard_control_mode();
void publish_trajectory_setpoint();
void publish_vehicle_command(uint16_t command, float param1 = 0.0, float param2 = 0.0);
void publish_vehicle_attitude_setpoint();
};
/**
* @brief Send a command to Arm the vehicle
*/
void OffboardControl::arm()
{
publish_vehicle_command(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1.0);
RCLCPP_INFO(this->get_logger(), "Arm command send");
}
/**
* @brief Send a command to Disarm the vehicle
*/
void OffboardControl::disarm()
{
publish_vehicle_command(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0.0);
RCLCPP_INFO(this->get_logger(), "Disarm command send");
}
/**
* @brief Publish the offboard control mode.
* For this example, only position and altitude controls are active.
*/
void OffboardControl::publish_offboard_control_mode()
{
OffboardControlMode msg{};
msg.position = false;
msg.velocity = false;
msg.acceleration = false;
msg.attitude = true;
msg.body_rate = false;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
offboard_control_mode_publisher_->publish(msg);
}
/**
* @brief Publish a trajectory setpoint
* For this example, it sends a trajectory setpoint to make the
* vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
void OffboardControl::publish_trajectory_setpoint()
{
TrajectorySetpoint msg{};
msg.position = {0.0, 0.0, -5.0};
msg.yaw = -3.14; // [-PI:PI]
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
trajectory_setpoint_publisher_->publish(msg);
}
void OffboardControl::publish_vehicle_attitude_setpoint()
{
VehicleAttitudeSetpoint msg{};
uint64_t now_ns = this->get_clock()->now().nanoseconds();
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
time_counter_ += 0.1f;
double roll = 0, pitch = 0, yaw = 0 ;
roll =(M_PI/7.2)*sin(M_PI*time_counter_/ 15);
pitch =(M_PI/7.2)*cos(M_PI*time_counter_/ 15);
yaw =(M_PI)*cos(M_PI*time_counter_/ 30);
//roll =(M_PI/9);
//pitch =(M_PI/9);
//yaw = (M_PI/4);
// Convert roll, pitch, yaw to quaternion
std::array<float, 4> q_d = quat_from_euler(roll, pitch, yaw); // Function to convert Euler angles to quaternion
// Set the desired attitude quaternion
msg.q_d = q_d;
msg.thrust_body = {0.0, 0.0, -0.4}; // Thrust to keep the drone in the air
RCLCPP_INFO(this->get_logger(), "q_d: [%.3f, %.3f, %.3f, %.3f]", q_d[0], q_d[1], q_d[2], q_d[3]);
RCLCPP_INFO(this->get_logger(), "thrust_body: [%.3f, %.3f, %.3f]", msg.thrust_body[0], msg.thrust_body[1], msg.thrust_body[2]);
vehicle_attitude_setpoint_publisher_->publish(msg);
RCLCPP_INFO(this->get_logger(),"Time: %.3f sec",now_ns/1e9);
}
std::array<float, 4> OffboardControl::quat_from_euler(double roll, double pitch, double yaw)
{
std::array<float, 4> q{};
double cy = cos(yaw * 0.5);
double sy = sin(yaw * 0.5);
double cp = cos(pitch * 0.5);
double sp = sin(pitch * 0.5);
double cr = cos(roll * 0.5);
double sr = sin(roll * 0.5);
// Calculate the quaternion components
q[0] = cr * cp * cy + sr * sp * sy; // w
q[1] = sr * cp * cy - cr * sp * sy; // x
q[2] = cr * sp * cy + sr * cp * sy; // y
q[3] = cr * cp * sy - sr * sp * cy; // z
return q;
}
/**
* @brief Publish vehicle commands
* @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
* @param param1 Command parameter 1
* @param param2 Command parameter 2
*/
void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
{
VehicleCommand msg{};
msg.param1 = param1;
msg.param2 = param2;
msg.command = command;
msg.target_system = 1;
msg.target_component = 1;
msg.source_system = 1;
msg.source_component = 1;
msg.from_external = true;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
vehicle_command_publisher_->publish(msg);
}
int main(int argc, char *argv[])
{
std::cout << "Starting offboard control node..." << std::endl;
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<OffboardControl>());
rclcpp::shutdown();
return 0;
}
```
### circle
```javascript=
/**
* @brief Offboard control example
* @file offboard_control.cpp
* @addtogroup examples
* @author Mickey Cowden <info@cowden.tech>
* @author Nuno Marques <nuno.marques@dronesolutions.io>
*/
#include <px4_msgs/msg/offboard_control_mode.hpp>
#include <px4_msgs/msg/trajectory_setpoint.hpp>
#include <px4_msgs/msg/vehicle_command.hpp>
#include <px4_msgs/msg/vehicle_control_mode.hpp>
#include <rclcpp/rclcpp.hpp>
#include <stdint.h>
#include <chrono>
#include <iostream>
using namespace std::chrono;
using namespace std::chrono_literals;
using namespace px4_msgs::msg;
class OffboardControl : public rclcpp::Node
{
public:
OffboardControl() : Node("offboard_control")
{
offboard_control_mode_publisher_ = this->create_publisher<OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
trajectory_setpoint_publisher_ = this->create_publisher<TrajectorySetpoint>("/fmu/in/trajectory_setpoint", 10);
vehicle_command_publisher_ = this->create_publisher<VehicleCommand>("/fmu/in/vehicle_command", 10);
offboard_setpoint_counter_ = 0;
auto timer_callback = [this]() -> void {
if (offboard_setpoint_counter_ == 10) {
// Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
}
// offboard_control_mode needs to be paired with trajectory_setpoint
publish_offboard_control_mode();
publish_trajectory_setpoint();
// stop the counter after reaching 11
if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
}
};
timer_ = this->create_wall_timer(10ms, timer_callback);
}
void arm();
void disarm();
private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<OffboardControlMode>::SharedPtr offboard_control_mode_publisher_;
rclcpp::Publisher<TrajectorySetpoint>::SharedPtr trajectory_setpoint_publisher_;
rclcpp::Publisher<VehicleCommand>::SharedPtr vehicle_command_publisher_;
std::atomic<uint64_t> timestamp_; //!< common synced timestamped
uint64_t offboard_setpoint_counter_; //!< counter for the number of setpoints sent
double time_counter_ = 0.0;
void publish_offboard_control_mode();
void publish_trajectory_setpoint();
void publish_vehicle_command(uint16_t command, float param1 = 0.0, float param2 = 0.0);
};
/**
* @brief Send a command to Arm the vehicle
*/
void OffboardControl::arm()
{
publish_vehicle_command(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1.0);
RCLCPP_INFO(this->get_logger(), "Arm command send");
}
/**
* @brief Send a command to Disarm the vehicle
*/
void OffboardControl::disarm()
{
publish_vehicle_command(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0.0);
RCLCPP_INFO(this->get_logger(), "Disarm command send");
}
/**
* @brief Publish the offboard control mode.
* For this example, only position and altitude controls are active.
*/
void OffboardControl::publish_offboard_control_mode()
{
OffboardControlMode msg{};
msg.position = true;
msg.velocity = false;
msg.acceleration = false;
msg.attitude = false;
msg.body_rate = false;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
offboard_control_mode_publisher_->publish(msg);
}
/**
* @brief Publish a trajectory setpoint
* For this example, it sends a trajectory setpoint to make the
* vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
void OffboardControl::publish_trajectory_setpoint()
{
// **圓形軌跡參數**
const float R = 30.0f; // 半徑
const float omega = 0.19f; // 控制運動速度
// **時間遞增**
time_counter_ += 0.01f; // 適當調整,確保 PX4 能跟上
// **計算圓形軌跡**
float x = R * std::cos(omega * time_counter_);
float y = R * std::sin(omega * time_counter_);
double z = -7.0f + 1.0f * std::sin(omega *time_counter_);; // 固定高度
double yaw = 0.0;//std::atan2(-y, -x); // 讓機頭始終面向軌跡方向
TrajectorySetpoint msg{};
msg.position = {static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)};
msg.yaw = yaw;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
trajectory_setpoint_publisher_->publish(msg);
}
/**
* @brief Publish vehicle commands
* @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
* @param param1 Command parameter 1
* @param param2 Command parameter 2
*/
void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
{
VehicleCommand msg{};
msg.param1 = param1;
msg.param2 = param2;
msg.command = command;
msg.target_system = 1;
msg.target_component = 1;
msg.source_system = 1;
msg.source_component = 1;
msg.from_external = true;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
vehicle_command_publisher_->publish(msg);
}
int main(int argc, char *argv[])
{
std::cout << "Starting offboard control node..." << std::endl;
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<OffboardControl>());
rclcpp::shutdown();
return 0;
}
```
### eight
```javascript=
/**
* @brief Offboard control example
* @file offboard_control.cpp
* @addtogroup examples
* @author Mickey Cowden <info@cowden.tech>
* @author Nuno Marques <nuno.marques@dronesolutions.io>
*/
#include <px4_msgs/msg/offboard_control_mode.hpp>
#include <px4_msgs/msg/trajectory_setpoint.hpp>
#include <px4_msgs/msg/vehicle_command.hpp>
#include <px4_msgs/msg/vehicle_control_mode.hpp>
#include <rclcpp/rclcpp.hpp>
#include <stdint.h>
#include <chrono>
#include <iostream>
using namespace std::chrono;
using namespace std::chrono_literals;
using namespace px4_msgs::msg;
class OffboardControl : public rclcpp::Node
{
public:
OffboardControl() : Node("offboard_control")
{
offboard_control_mode_publisher_ = this->create_publisher<OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
trajectory_setpoint_publisher_ = this->create_publisher<TrajectorySetpoint>("/fmu/in/trajectory_setpoint", 10);
vehicle_command_publisher_ = this->create_publisher<VehicleCommand>("/fmu/in/vehicle_command", 10);
offboard_setpoint_counter_ = 0;
auto timer_callback = [this]() -> void {
if (offboard_setpoint_counter_ == 10) {
// Change to Offboard mode after 10 setpoints
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
// Arm the vehicle
this->arm();
}
// offboard_control_mode needs to be paired with trajectory_setpoint
publish_offboard_control_mode();
publish_trajectory_setpoint();
// stop the counter after reaching 11
if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
}
};
timer_ = this->create_wall_timer(10ms, timer_callback);
}
void arm();
void disarm();
private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<OffboardControlMode>::SharedPtr offboard_control_mode_publisher_;
rclcpp::Publisher<TrajectorySetpoint>::SharedPtr trajectory_setpoint_publisher_;
rclcpp::Publisher<VehicleCommand>::SharedPtr vehicle_command_publisher_;
std::atomic<uint64_t> timestamp_; //!< common synced timestamped
uint64_t offboard_setpoint_counter_; //!< counter for the number of setpoints sent
double time_counter_ = 0.0;
void publish_offboard_control_mode();
void publish_trajectory_setpoint();
void publish_vehicle_command(uint16_t command, float param1 = 0.0, float param2 = 0.0);
};
/**
* @brief Send a command to Arm the vehicle
*/
void OffboardControl::arm()
{
publish_vehicle_command(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1.0);
RCLCPP_INFO(this->get_logger(), "Arm command send");
}
/**
* @brief Send a command to Disarm the vehicle
*/
void OffboardControl::disarm()
{
publish_vehicle_command(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0.0);
RCLCPP_INFO(this->get_logger(), "Disarm command send");
}
/**
* @brief Publish the offboard control mode.
* For this example, only position and altitude controls are active.
*/
void OffboardControl::publish_offboard_control_mode()
{
OffboardControlMode msg{};
msg.position = true;
msg.velocity = false;
msg.acceleration = false;
msg.attitude = false;
msg.body_rate = false;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
offboard_control_mode_publisher_->publish(msg);
}
/**
* @brief Publish a trajectory setpoint
* For this example, it sends a trajectory setpoint to make the
* vehicle hover at 5 meters with a yaw angle of 180 degrees.
*/
void OffboardControl::publish_trajectory_setpoint()
{
// **八字形參數**
const float A = 25.0f; // X 軸擺幅
const float B = 25.0f; // Y 軸擺幅
const float omega = 0.16f; // 控制運動速度
// **時間遞增**
time_counter_ += 0.01f; // 減少變化幅度,讓 PX4 能跟上
// **計算八字形軌跡**
float x = A * std::sin(omega*time_counter_);
float y = B * std::sin(omega*time_counter_) * std::cos(omega*time_counter_);
double z = -20.0f + 0.5f * std::sin(omega*time_counter_); // 固定高度
double yaw = 0.0; // 保持機頭朝前
TrajectorySetpoint msg{};
msg.position = {static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)};
msg.yaw = yaw;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
trajectory_setpoint_publisher_->publish(msg);
}
/**
* @brief Publish vehicle commands
* @param command Command code (matches VehicleCommand and MAVLink MAV_CMD codes)
* @param param1 Command parameter 1
* @param param2 Command parameter 2
*/
void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
{
VehicleCommand msg{};
msg.param1 = param1;
msg.param2 = param2;
msg.command = command;
msg.target_system = 1;
msg.target_component = 1;
msg.source_system = 1;
msg.source_component = 1;
msg.from_external = true;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
vehicle_command_publisher_->publish(msg);
}
int main(int argc, char *argv[])
{
std::cout << "Starting offboard control node..." << std::endl;
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<OffboardControl>());
rclcpp::shutdown();
return 0;
}
```
```javascript=
#find USB
ls /dev/ttyUSB*
#offboard
micrortps_agent -b 57600 -d /dev/ttyUSB0 #terminal1
micrortps_client start -b 57600 -d /dev/ttyS1 #QGCterminal
source ~/px4_ros_com_ros2/install/setup.bash #terminal3
ros2 run px4_ros_com offboard_control #terminal3
source ~/px4_ros_com_ros2/install/setup.bash
#clean ros2
cd ~/px4_ros_com_ros2/src/px4_ros_com/scripts
source clean_all.bash
#build ros2 workspace
cd ~/px4_ros_com_ros2/src/px4_ros_com/scripts
source build_ros2_workspace.bash
source build_ros2_workspace.bash --verbose||true #顯示編譯過程
#ulog2csv
vehicle attitude
actuator control
-------------------------------------------------------------------------------------------------------
simulation :
cd ~/PX4-Autopilot/ -------> make px4_sitl_rtps gazebo
QGroundcontrol :
cd ~/Downloads/ -----------> ./QGroundControl.AppImage
-------------------------------------------------------------------------------------------------------
*************************************** About Git ***************************************
Q: What is git?
A: 方便控制代碼版本的軟體(未來想走韌體or軟體必學,學會了比較好找工作)or Google What is Git
本電腦的 GOOGLE & Github 帳號密碼在白板上,為游老師的帳號密碼
Github Name : Modern Control - Lab
以往是git clone PX4的代碼至本機,但是為了方便開發,希望先 fork 至 本實驗室的 github上
再 git clone 至本機,進行版本控制
*************************************** git 指令 ***************************************
git status //查看狀態
git branch //查看支線
git branch "輸入新支線名稱" //創立新的支線
git chekcout "輸入支線名稱" //切換至該支線
git pull //將本地端儲存庫的程式碼更新與遠端儲存庫(github)一樣,不太理解可以上網查git clone vs git pull
//另外 git pull = git fetch + git merge
git add "輸入修過檔案的名稱" //此步驟會先將修改過得檔案放入 staged
git commit -m "修改內容或是做了神魔更動" //記住 git add 完畢後一定要git commit -m
git push //將git暫存的東西push到遠端儲存庫(github),完成此次修改
```