Skip to content

Commit

Permalink
AP_DDS: Add local pose publisher
Browse files Browse the repository at this point in the history
  • Loading branch information
pedro-fuoco committed Apr 14, 2023
1 parent 9e9d487 commit 2ff8418
Show file tree
Hide file tree
Showing 4 changed files with 105 additions and 0 deletions.
60 changes: 60 additions & 0 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,14 @@
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_AHRS/AP_AHRS.h>

#include "AP_DDS_Client.h"


static constexpr uint16_t DELAY_TIME_TOPIC_MS = 10;
static constexpr uint16_t DELAY_NAV_SAT_FIX_TOPIC_MS = 1000;
static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = 33;
static char WGS_84_FRAME_ID[] = "WGS-84";
// https://www.ros.org/reps/rep-0105.html#base-link
static char BASE_LINK_FRAME_ID[] = "base_link";
Expand Down Expand Up @@ -160,6 +162,43 @@ void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg)

}

void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg)
{
update_topic(msg.header.stamp);
strcpy(msg.header.frame_id, BASE_LINK_FRAME_ID);

auto &ahrs = AP::ahrs();
WITH_SEMAPHORE(ahrs.get_semaphore());

// In ROS REP 103, axis orientation uses the ENU convention:
// X - East
// Y - North
// Z - Up
// https://www.ros.org/reps/rep-0103.html#axis-orientation
// In AP_AHRS, axis orientation uses the NED convention
// X - North
// Y - East
// Z - Down
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
// as well as and invert Z

Quaternion orientation;
if (ahrs.get_quaternion(orientation))
{
msg.pose.orientation.x = orientation[2];
msg.pose.orientation.y = orientation[1];
msg.pose.orientation.z = -orientation[3];
msg.pose.orientation.w = orientation[0];
}

Vector3f position;
if (ahrs.get_relative_position_NED_home(position))
{
msg.pose.position.x = position[1];
msg.pose.position.y = position[0];
msg.pose.position.z = -position[2];
}
}

/*
class constructor
Expand Down Expand Up @@ -339,6 +378,21 @@ void AP_DDS_Client::write_static_transforms()
}
}

void AP_DDS_Client::write_local_pose_topic()
{
WITH_SEMAPHORE(csem);
if (connected) {
ucdrBuffer ub;
const uint32_t topic_size = geometry_msgs_msg_PoseStamped_size_of_topic(&local_pose_topic, 0);
uxr_prepare_output_stream(&session,reliable_out,topics[3].dw_id,&ub,topic_size);
const bool success = geometry_msgs_msg_PoseStamped_serialize_topic(&ub, &local_pose_topic);
if (!success) {
// TODO sometimes serialization fails on bootup. Determine why.
// AP_HAL::panic("FATAL: DDS_Client failed to serialize\n");
}
}
}

void AP_DDS_Client::update()
{
WITH_SEMAPHORE(csem);
Expand All @@ -358,6 +412,12 @@ void AP_DDS_Client::update()
write_nav_sat_fix_topic();
}

if (cur_time_ms - last_local_pose_time_ms > DELAY_LOCAL_POSE_TOPIC_MS) {
update_topic(local_pose_topic);
last_local_pose_time_ms = cur_time_ms;
write_local_pose_topic();
}

connected = uxr_run_session_time(&session, 1);
}

Expand Down
7 changes: 7 additions & 0 deletions libraries/AP_DDS/AP_DDS_Client.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

#include "sensor_msgs/msg/NavSatFix.h"
#include "tf2_msgs/msg/TFMessage.h"
#include "geometry_msgs/msg/PoseStamped.h"

#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Scheduler.h>
Expand Down Expand Up @@ -44,6 +45,7 @@ class AP_DDS_Client
builtin_interfaces_msg_Time time_topic;
sensor_msgs_msg_NavSatFix nav_sat_fix_topic;
tf2_msgs_msg_TFMessage static_transforms_topic;
geometry_msgs_msg_PoseStamped local_pose_topic;

HAL_Semaphore csem;

Expand All @@ -53,11 +55,14 @@ class AP_DDS_Client
static void update_topic(builtin_interfaces_msg_Time& msg);
static void update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance);
static void populate_static_transforms(tf2_msgs_msg_TFMessage& msg);
static void update_topic(geometry_msgs_msg_PoseStamped& msg);

// The last ms timestamp AP_DDS wrote a Time message
uint64_t last_time_time_ms;
// The last ms timestamp AP_DDS wrote a NavSatFix message
uint64_t last_nav_sat_fix_time_ms;
// The last ms timestamp AP_DDS wrote a Local Pose message
uint64_t last_local_pose_time_ms;


public:
Expand All @@ -81,6 +86,8 @@ class AP_DDS_Client
void write_nav_sat_fix_topic();
//! @brief Serialize the static transforms and publish to the IO stream(s)
void write_static_transforms();
//! @brief Serialize the current local pose and publish to the IO stream(s)
void write_local_pose_topic();
//! @brief Update the internally stored DDS messages with latest data
void update();

Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_DDS/AP_DDS_Topic_Table.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,4 +42,14 @@ const struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
.deserialize = Generic_deserialize_topic_fn_t(&tf2_msgs_msg_TFMessage_deserialize_topic),
.size_of = Generic_size_of_topic_fn_t(&tf2_msgs_msg_TFMessage_size_of_topic),
},
{
.topic_id = 0x04,
.pub_id = 0x04,
.dw_id = uxrObjectId{.id=0x04, .type=UXR_DATAWRITER_ID},
.topic_profile_label = "localpose__t",
.dw_profile_label = "localpose__dw",
.serialize = Generic_serialize_topic_fn_t(&geometry_msgs_msg_PoseStamped_serialize_topic),
.deserialize = Generic_deserialize_topic_fn_t(&geometry_msgs_msg_PoseStamped_deserialize_topic),
.size_of = Generic_size_of_topic_fn_t(&geometry_msgs_msg_PoseStamped_size_of_topic),
},
};
28 changes: 28 additions & 0 deletions libraries/AP_DDS/dds_xrce_profile.xml
Original file line number Diff line number Diff line change
Expand Up @@ -86,4 +86,32 @@
</historyQos>
</topic>
</data_writer>
<topic profile_name="localpose__t">
<name>rt/ROS2_LocalPose</name>
<dataType>geometry_msgs::msg::dds_::PoseStamped_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>5</depth>
</historyQos>
</topic>
<data_writer profile_name="localpose__dw">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
<qos>
<reliability>
<kind>BEST_EFFORT</kind>
</reliability>
<durability>
<kind>VOLATILE</kind>
</durability>
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_LocalPose</name>
<dataType>geometry_msgs::msg::dds_::PoseStamped_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>5</depth>
</historyQos>
</topic>
</data_writer>
</profiles>

0 comments on commit 2ff8418

Please sign in to comment.