์๋ !
ROS ์ฃผ์ ๋ฅผ ํตํด ์ผ๋ถ ๋นํ ์ ๋ณด๋ฅผ ๋ณด๋ด๋ ๋นํ๊ธฐ ์๋ฎฌ๋ ์ดํฐ๊ฐ ์์ต๋๋ค. MAVLink๋ฅผ ์ฌ์ฉํ์ฌ ๊ฐ์ ธ ์์ QGroundControl๋ก ๋ณด๋ด๊ณ ์ถ์ต๋๋ค.
์๋ ๋ฐฉ์ ํ ์คํธ๋ฅผ ์์ํ๊ธฐ ์ํด ๊ฐ์ง ๋ฐฐํฐ๋ฆฌ ์ํ(mavros_msgs/BatteryStatus.msg)๋ก ํ๋์ ๋ฉ์์ง๋ฅผ ๋ณด๋ด๋ ค๊ณ ํ์ต๋๋ค.
1 - ๋จผ์ gcs_url = udp://:[email protected] :14551๋ก mavros_node๋ฅผ ์คํํฉ๋๋ค.
2 - ๋ฐฐํฐ๋ฆฌ ๋ฉ์์ง๋ฅผ ๋ณด๋ด์ผ ํ๋ ๋
ธ๋๋ฅผ ์คํํฉ๋๋ค.
#include <ros/ros.h>
#include <mavros_msgs/BatteryStatus.h>
int main(int argc, char *argv[])
{
ros::init(argc, argv, "battery_node");
ros::NodeHandle n;
ros::Publisher battery_pub = n.advertise<mavros_msgs::BatteryStatus>("/mavros/battery", 1000);
ros::Rate loop_rate(10);
while (ros::ok())
{
mavros_msgs::BatteryStatus baterry_msg;
baterry_msg.voltage = 5;
baterry_msg.current = 0.5;
baterry_msg.remaining = 0.36;
battery_pub.publish(baterry_msg);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
3 - QGroundControl์ UDP์ ์ฐ๊ฒฐํฉ๋๋ค: 127.0.0.1:14551
... ๊ทธ๋ฆฌ๊ณ ์๋ฌด ์ผ๋ ์ผ์ด๋์ง ์์ต๋๋ค =/
mavros์ QGC ๊ฐ์ ์ฐ๊ฒฐ์ด ์๋ํ๋ค๊ณ ํ์ ํฉ๋๋ค. 127.0.0.1:14540์ ํตํด MAVProxy๋ก ์๋ฎฌ๋ ์ด์ ์ ์คํํ๊ณ mavros๋ฅผ "๋ธ๋ฆฌ์ง"๋ก ์ฌ์ฉํ๋ฉด ๋นํ๊ธฐ๊ฐ ์ธ์๋๊ธฐ ๋๋ฌธ์ ๋๋ค.
๋ด๊ฐ ๋ญ ์๋ชปํ๊ณ ์์ฃ ?
Ubuntu 14, ROS Indigo ๋ฐ QGC 2.9.7์ ์ฌ์ฉํ๊ณ ์์ต๋๋ค.
๋ฏธ๋ฆฌ ๊ฐ์ฌ๋๋ฆฝ๋๋ค.
ํ๋ธ๋ก
sys_status : ๋ณด์๋ค์ํผ mavros๋ ๊ตฌ๋ ์๊ฐ ์๋ _publisher_์ ๋๋ค.
์๋ ํ์ธ์ voun๋
๋ต๋ณ ์ฃผ์ ์ ๊ฐ์ฌํฉ๋๋ค. ์ ๊ฐ ์ ์ดํดํ๋ค๋ฉด ์ด ๋ฉ์์ง๋ ๋ณด๋ผ ์ ์๊ณ , ROS์์๋ง ์์ ํด์ ๋ณด์ฌ์ฃผ๋๋ฐ ๋ง๋์?
๊ทธ๋ฐ ๋ค์ _mavlink/to_๋ฅผ ์ฌ์ฉํ์ฌ ํด๋น ๋ฉ์์ง๋ฅผ ๋ณด๋ผ ์ ์์ต๋๊น?
์ด๋ป๊ฒ ํ ์ ์์ต๋๊น?
๋ค์ ํ๋ฒ ๊ฐ์ฌํฉ๋๋ค!
mavlink/to
๋ GCS๊ฐ ์๋ FCU์ ๋ฉ์์ง ๋ฅผ ๋ณด๋
๋๋ค.
๊ทธ๋ฌ๋ gcs_bridge ๋
ธ๋์ mavlink/from
์ฃผ์ ๋ฅผ ์ฌ์ฉํ ์ ์์ต๋๋ค.
์๋ ๋ค์,
์ข์, ๊ฐ๋จํ ํํธ๋นํธ ๋ฉ์์ง๋ฅผ ๋ณด๋ด๋๋ก ์ฝ๋๋ฅผ ๋ณ๊ฒฝํ์ต๋๋ค.
#include <ros/ros.h>
#include <mavros_msgs/Mavlink.h>
int main(int argc, char **argv){
ros::init(argc, argv, "hertbeat_publisher");
ros::NodeHandle n;
ros::Publisher example_pub = n.advertise<mavros_msgs::Mavlink>("/mavlink/from", 1000);
ros::Rate loop_rate(1); // 1 Hz
mavros_msgs::Mavlink mavlink_msg;
mavlink_msg.len = 2;
mavlink_msg.sysid = 1;
mavlink_msg.compid = 1;
mavlink_msg.msgid = 0;
std::vector<long unsigned int> payload64(7, 0);
mavlink_msg.payload64 = payload64;
while (ros::ok())
{
mavlink_msg.header.stamp = ros::Time::now();
if (mavlink_msg.seq < 255){
mavlink_msg.seq++;
}
else {mavlink_msg.seq = 0;}
// publish message
example_pub.publish(mavlink_msg);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
1 - fcu_url=udp://:14540@ ๋ฐ gcs_url = udp://:[email protected] :14551๋ก
[ INFO] [1468659493.280504313]: FCU URL: udp://:14540@
[ INFO] [1468659493.289025098]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1468659493.289457240]: GCS URL: udp://:[email protected]:14551
[ INFO] [1468659493.289691565]: udp1: Bind address: 0.0.0.0:14570
[ INFO] [1468659493.289824558]: udp1: Remote address: 127.0.0.1:14551
...
[ INFO] [1468659494.906066742]: MAVROS started. MY ID 1.240, TARGET ID 1.1
2 - gcs_url:='udp://@127.0.0.1'๋ก gcs_bridge๋ฅผ ์คํํ์ฌ ๋ค์์ ์ป์ต๋๋ค.
[ INFO] [1468659758.392659411]: udp0: Bind address: 0.0.0.0:14555
[ INFO] [1468659758.392800665]: udp0: Remote address: 127.0.0.1:14550
3 - ์์ ๋
ธ๋๋ฅผ ์คํํ์ฌ 1Hz์์ /mavlink/from์ ๊ฒ์ํฉ๋๋ค.
4 - ์์คํ
ID 1์ ์ฌ์ฉํ์ฌ UDP 127.0.0.1:14550์ ์ฌ์ฉํ์ฌ QGroundControl์ ์ฐ๊ฒฐํฉ๋๋ค.
... ๊ทธ๋ฆฌ๊ณ ๋ค์ MAVLink ์ธ์คํํฐ๊ฐ ๋น์ด ์์ต๋๋ค.
์ฒ์์๋ ์๋ฌด ์ผ๋ ์ผ์ด๋์ง ์์ง๋ง ์ด๋ ์์ ์์ QGroundControl์์ ๋ค์ ์ค๋ฅ๊ฐ ๋ฐ์ํฉ๋๋ค.
MAVLink ๋ฒ์ ๋๋ ์ ์ก ์๋ ๋ถ์ผ์น๊ฐ ์์ต๋๋ค. QGroundControl๊ณผ ์๋ ์กฐ์ข ์ฅ์น์ ์ ์ก ์๋๊ฐ ๋์ผํ์ง ํ์ธํ์ญ์์ค.
๋๋ ์ด๋ป๊ฒ ๋ QGC๊ฐ์ด ์ค๋ฅ๊ฐ ๋ฐ์ํ๊ธฐ ์ ์ UDP ํฌํธ๋ฅผ ๋ณ๊ฒฝํ๋ค๊ณ ์๊ฐํฉ๋๋ค.
๋ด๊ฐ ๋ญ ์๋ชปํ๊ณ ์์ฃ ?
๊ฐ์ฌ!
a) gcs_url
์ ๋ง๋ธ๋ก๋ฅผ ์ฌ์ฉํ์ง ๋ง์ธ์! gcs_bridge
์ฐ๊ฒฐํด์ผ ํฉ๋๋ค!
b) Mavlink.msg๋ฅผ ์ฑ์ฐ๊ธฐ ์ํ ์๋ชป๋ ์ฝ๋. ๋ค์๊ณผ ๊ฐ์์ผ ํฉ๋๋ค.
mavlink::common::msg::HEARTBEAT hb{};
...
mavlink::mavlink_message_t msg;
mavlink::MsgMap map(msg);
hb.serialize(map);
mavlink::finalize_message_buffer(&msg, sysid, compid, ...);
mavros_msgs::Mavlink ml;
mavros_msgs::mavlink::convert(msg, ml);
๋ณด๋ค:
์๋ !
๊ฐ์ฌ! ๋๋์ด ์ฑ๊ณตํ์ต๋๋ค. Indigo๋ฅผ ์ฌ์ฉํ๊ธฐ ๋๋ฌธ์ ๋ค๋ฅธ ํด๋์ค๋ฅผ ์ฌ์ฉํ์ต๋๋ค. ๋ค๋ฅธ ์ฌ๋์ด ์ ํํ ์ํํ๋ ๋ฐฉ๋ฒ์ ๊ถ๊ธํดํ๋ ๊ฒฝ์ฐ๋ฅผ ๋๋นํ์ฌ ์ฌ๊ธฐ์ ์ฝ๋๋ฅผ ๋จ๊น๋๋ค. ํํธ๋นํธ์ ๊ณ ๋ ๋ฉ์์ง๋ฅผ ๋ณด๋ด๊ณ QGroundControl์์ ์์ ํฉ๋๋ค.
1- fcu_url=udp://:14540@ ๋ฐ gcs_url= udp://:[email protected] :14551๋ก mavros ๋
ธ๋๋ฅผ ์์ํฉ๋๋ค.
2- gcs_url:=udp://@127.0.0.1:14560์ผ๋ก gcs_bridge๋ฅผ ์์ํฉ๋๋ค.
3- ์ด ๋
ธ๋๋ฅผ ์์ํฉ๋๋ค.
#include <ros/ros.h>
#include <mavconn/interface.h>
#include <mavros_msgs/Mavlink.h>
#include <mavros_msgs/mavlink_convert.h>
// General parameters
uint8_t system_id = 1;
uint8_t component_id = 1;
uint8_t type = 1;
uint8_t autopilot = 0;
uint8_t base_mode = 128;
uint32_t custom_mode = 0;
uint8_t system_status = 0;
// Parameters of the altitude message
float alt_monotonic = 10.0;
float alt_amsl = 100;
float alt_local = 10.0;
float alt_relative = 10.0;
float alt_terrain = 10;
float bottom_clearance = 0;
int main(int argc, char **argv){
// Create heartbeat message
mavlink_message_t msg_heartbeat;
mavlink_msg_heartbeat_pack(system_id, component_id, &msg_heartbeat, type, autopilot, base_mode, custom_mode, system_status);
mavros_msgs::Mavlink ml_heartbeat;
mavros_msgs::mavlink::convert(msg_heartbeat, ml_heartbeat);
// Create altitude message
mavlink_message_t msg_altitude;
mavros_msgs::Mavlink ml_altitude;
ros::init(argc, argv, "telemetry_publisher");
ros::NodeHandle n;
ros::Publisher example_pub = n.advertise<mavros_msgs::Mavlink>("/mavlink/from", 1000);
ros::Rate loop_rate(1); // 1 Hz
while (ros::ok())
{
uint64_t time_stamp = ros::Time::now().nsec;
// Finish altitude message
mavlink_msg_altitude_pack(system_id, component_id, &msg_altitude, time_stamp, alt_monotonic, alt_amsl, alt_local, alt_relative, alt_terrain, bottom_clearance);
mavros_msgs::mavlink::convert(msg_altitude, ml_altitude);
// Publish messages
example_pub.publish(ml_heartbeat);
example_pub.publish(ml_altitude);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
4- QGroundControl์ ์์ํ๊ณ 127.0.0.1:14560์์ ์ฐ๊ฒฐ์ ๊ตฌ์ฑํฉ๋๋ค.
MavLink Inspector๋ฅผ ์ด๋ฉด ๋๋ต ~1Hz์์ ํํธ๋นํธ์ ๊ณ ๋ ๋ฉ์์ง๊ฐ ํ์๋์ด์ผ ํฉ๋๋ค.
๋๋ ์ด๊ฒ์ ์๋ํ์ง๋ง ์ค๋ฅ๊ฐ ๋ฐ์ํฉ๋๋ค. ์ ๊ทธ๋ฐ์ง ์ดํดํ ์ ์์ต๋๋ค. ์๋ฌด๋ ๋๋ฅผ ๋์ธ ์ ์์ต๋๊น?
mavlink_msg_heartbeat_pack ํจ์๋ #include ๋ ํฌํจ๋์ด์ผ ํฉ๋๋ค.
cmake์์ ๋ด๊ฐ ํ๋ ธ์ ์ ์์ต๋๊น?
#include "ros/ros.h"
#include <mavros_msgs/mavlink_convert.h>
#include <mavconn/interface.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "talker");
ros::NodeHandle n;
ros::Publisher pub = n.advertise<mavros_msgs::Mavlink>("/mavlink/from", 1000);
ros::Rate loop_rate(10);
uint8_t system_id = 1;
uint8_t component_id = 1;
uint8_t type = 1;
uint8_t autopilot = 0;
uint8_t base_mode = 128;
uint32_t custom_mode = 0;
uint8_t system_status = 0;
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(system_id, component_id, &msg, type, autopilot, base_mode, custom_mode, system_status);
return 0;
}
cmake_minimum_required(VERSION 2.8.3)
project(talker)
find_package(catkin REQUIRED COMPONENTS mavros mavros_msgs mavlink)
catkin_package()
include(EnableCXX11)
include(MavrosMavlink)
include_directories(
${catkin_INCLUDE_DIRS}
${mavlink_INCLUDE_DIRS}
)
add_executable(talker talker.cpp)
target_link_libraries(talker ${catkin_LIBRARIES})
์ค๋ฅ: 'mavlink_message_t'๊ฐ ์ด ๋ฒ์์์ ์ ์ธ๋์ง ์์์ต๋๋ค.
mavlink_message_t ๋ฉ์์ง;
์ค๋ฅ: 'mavlink_msg_heartbeat_pack'์ด ์ด ๋ฒ์์์ ์ ์ธ๋์ง ์์์ต๋๋ค.
mavlink_msg_heartbeat_pack(system_id, component_id, &msg, ์ ํ, ์๋ ์กฐ์ข
์ฅ์น, base_mode, custom_mode, system_status);
@shawinmihail mavros์ ๋ฒ์ ์ ๋ฌด์์ ๋๊น? 0.18+์๋ mavlink_helpers.h ๋ฐ C++11 lib๋ง ํฌํจ๋ฉ๋๋ค.
๋ด ๋ฌธ์ ์ ํด๊ฒฐ์ฑ ์ ์ฐพ์์ต๋๋ค. ์๋ง๋ mavros v0.18+๋ mavlink v2.0 ํค๋๋ง ์ฌ์ฉํฉ๋๋ค. ๋ฉ์์ง๋ฅผ ์์ฑํ๋ ค๋ฉด msg_name_pack() ๋์ MsgMap.serialize()๋ฅผ ์ฌ์ฉํด์ผ ํฉ๋๋ค.
mavlink::mavlink_message_t msg;
mavlink::MsgMap map(msg);
mavlink::groupcontrol::msg::GROUP_COEFFS_PART1 msgPart1 //my custom msg;
msgPart1.kc = kc;
msgPart1.ks = ks;
//........................... - fill msg
msgPart1.serialize(map);
map.reset();
auto mi = msgPart1.get_message_info();
mavlink::mavlink_finalize_message(&msg, system_id, component_id, mi.min_length, mi.length, mi.crc_extra);
mavros_msgs::Mavlink mavrosMsg;
mavros_msgs::mavlink::convert(msg, mavrosMsg);
์ด์ฉ๋ฉด ๋๊ตฐ๊ฐ๋ฅผ ๋์ธ ์ ์์ต๋๋ค. ๋ ๋์ ๋ฐฉ๋ฒ์ ์๊ณ ์๋ค๋ฉด pls๋ฅผ ์์ฑํ์ญ์์ค.
ํํธ๋ฅผ ์ฃผ์
์ ๊ฐ์ฌํฉ๋๋ค.
Message::serialize()
๋ MsgMap::reset()
๋ฅผ ์ํํ๋ฏ๋ก ์ง์ ํธ์ถํ์ง ๋ง์ญ์์ค! ๋ฉ์์ง๊ฐ ๊นจ์ง ์ ์์ต๋๋ค.
๋ํ MAVConnInterface
ํด๋์ค๊ฐ ์์ผ๋ฏ๋ก ์ฌ์ฉ์ ์ ์ gcs_bridge
๋ฅผ ์์ฑํ๋ ๊ฒ์ด ๋ ๋์ ๊ฒ์
๋๋ค. ์ฌ๊ธฐ์ ๋ฉ์์ง๋ฅผ ๋ณด๋ผ ์ ์์ต๋๋ค.
auto gcs_link = MAVConnInterface::open_url("udp-b://@");
mavlink::common::msg::HEARTBEAT hb{};
// fill hb
gcs_link->send_message_ignore_drop(hb);
@vooon , ๋๊ธ ๊ฐ์ฌํฉ๋๋ค. ๋ด ์๋ฃจ์ ์ด mavlink v1.0 ํ๋กํ ์ฝ์์ ์ฌ๋ฐ๋ฅด๊ฒ ์๋ํ์ง ์๋๋ค๋ ๊ฒ์ ์์์ต๋๋ค. ์ด์ ์๋ก์ด ๊ฒ์ ๋ง๋ค๊ณ ํ ์คํธํฉ๋๋ค. ์๋ํฉ๋๋ค!
#include "ros/ros.h"
#include <mavros_msgs/mavlink_convert.h>
#include <mavconn/interface.h>
#include <iostream>
#include <mavlink/v2.0/mavlink_helpers.h>
float kc = 0.0f; /*< gravity coeff */
float ks = 0.0f; /*< repulsive coeff */
float ka = 0.0f; /*< speed alignment coeff */
float kp = 0.0f; /*< chasing coeff */
float km = 0.0f; /*< waypoint gravity coeff */
float kh = 0.0f; /*< rotate speed coeff */
float vmax = 0.0f; /*< max autopilot velocity */
float rn = 0.0f; /*< search radius of groupmate */
float rs = 0.0f; /*< repulsiveOn radius */
float rm = 0.0f; /*< getting waypoint radius */
float rmb = 0.0f; /*< change gravity law radius */
void packMavlinkMessage(const mavlink::Message& mavMsg, mavros_msgs::Mavlink &rosMsg)
{
mavlink::mavlink_message_t msg;
mavlink::MsgMap map(msg);
mavMsg.serialize(map);
auto mi = mavMsg.get_message_info();
mavlink::mavlink_status_t *status = mavlink::mavlink_get_channel_status(mavlink::MAVLINK_COMM_0);
status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
mavlink::mavlink_finalize_message_buffer(&msg, 1, 1, status, mi.min_length, mi.length, mi.crc_extra);
mavros_msgs::mavlink::convert(msg, rosMsg);
}
void mavlinkCallback(const mavros_msgs::Mavlink& msg)
{
mavlink::mavlink_message_t mavMsg;
mavros_msgs::mavlink::convert(msg, mavMsg);
if(mavMsg.msgid == mavlink::groupcontrol::msg::SET_GROUP_PARAMS::MSG_ID)
{
ROS_WARN("SET GROUP_PARAMS");
mavlink::MsgMap map(mavMsg);
mavlink::groupcontrol::msg::SET_GROUP_PARAMS setParamsMsg;
setParamsMsg.deserialize(map);
std::cout << setParamsMsg.kc;
}
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "talker");
ros::NodeHandle n;
ros::Publisher pub = n.advertise<mavros_msgs::Mavlink>("/mavlink/from", 1000);
ros::Subscriber sub = n.subscribe("mavlink/to", 1000, mavlinkCallback);
ros::Rate loop_rate(10);
ROS_INFO("%s", "Talker started");
mavlink::groupcontrol::msg::GROUP_PARAMS msgPart1;
msgPart1.kc = kc;
msgPart1.ks = ks;
msgPart1.ka = ka;
msgPart1.kp = kp;
msgPart1.km = km;
msgPart1.kh = kh;
msgPart1.vmax = vmax;
msgPart1.rn = rn;
msgPart1.rs = rs;
msgPart1.rm = rm;
msgPart1.rmb = rmb;
while (ros::ok())
{
mavros_msgs::Mavlink mavrosMsg;
packMavlinkMessage(msgPart1, mavrosMsg);
pub.publish(mavrosMsg);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
๋๊ตฐ๊ฐ๊ฐ ๋๋ฅผ ๋์ธ ์ ์๊ณ ์ธ ์ ์์ต๋๋ค.
์๋ฅผ ๋ค์ด ํ์ด์ฌ์์ ์ด๋ป๊ฒ ๊ฐ์ ์ผ์ ํ ์ ์์ต๋๊น?
mavlink msg๋ฅผ ์์ฑํ๊ณ mavros msg๋ก ๋ณํํ์๊ฒ ์ต๋๊น?
๋ํ
MAVConnInterface
ํด๋์ค๊ฐ ์์ผ๋ฏ๋ก ์ฌ์ฉ์ ์ ์gcs_bridge
๋ฅผ ์์ฑํ๋ ๊ฒ์ด ๋ ๋์ ๊ฒ์ ๋๋ค. ์ฌ๊ธฐ์ ๋ฉ์์ง๋ฅผ ๋ณด๋ผ ์ ์์ต๋๋ค.auto gcs_link = MAVConnInterface::open_url("udp-b://@"); mavlink::common::msg::HEARTBEAT hb{}; // fill hb gcs_link->send_message_ignore_drop(hb);
์ด ๋ฐฉ๋ฒ์ ๋จ์ํ ์ฌ์ฉ์ ์ง์ ๋ฉ์์ง๋ฅผ ๋ณด๋ผ ์ ์์ง๋ง ์ํ์ด ์์ต๋๊น? @vooon
๊ฐ์ฅ ์ ์ฉํ ๋๊ธ
๋ํ
MAVConnInterface
ํด๋์ค๊ฐ ์์ผ๋ฏ๋ก ์ฌ์ฉ์ ์ ์gcs_bridge
๋ฅผ ์์ฑํ๋ ๊ฒ์ด ๋ ๋์ ๊ฒ์ ๋๋ค. ์ฌ๊ธฐ์ ๋ฉ์์ง๋ฅผ ๋ณด๋ผ ์ ์์ต๋๋ค.