Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Harderthan/messages #13

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion airsim_ros_pkgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,8 @@ target_link_libraries(airsim_settings_parser

set(ARISIM_SOURCES
src/airsim_ros_wrapper.cpp
src/command_subscriber.cpp)
src/command_subscriber.cpp
src/messages.cpp)
add_library(airsim_ros ${ARISIM_SOURCES})
add_dependencies(airsim_ros
${${PROJECT_NAME}_EXPORTED_TARGETS}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,8 @@ class AirsimClient {

airsim_ros_pkgs::GPSYaw GetHomeGeoPoint() const {
const auto origin_geo_point = airsim_client_robot_->getHomeGeoPoint("");
return utils::GetGpsMsgFromAirsimGeoPoint(origin_geo_point);
return messages::helper_functions::GetGpsMsgFromAirsimGeoPoint(
origin_geo_point);
}

private:
Expand Down
52 changes: 52 additions & 0 deletions airsim_ros_pkgs/include/airsim_ros_pkgs/messages.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,13 @@
#include <string>

#include "mavros_msgs/AttitudeTarget.h"
#include "nav_msgs/Odometry.h"
#include "sensor_msgs/Imu.h"
#include "sensor_msgs/MagneticField.h"
#include "sensor_msgs/NavSatFix.h"
#include "sensor_msgs/PointCloud2.h"
#include "sensor_msgs/Range.h"
#include "tf2/LinearMath/Quaternion.h"

// ROS custom msgs.
#include "airsim_ros_pkgs/Altimeter.h"
Expand All @@ -25,11 +32,56 @@

#include "common/AirSimSettings.hpp"
#include "common/CommonStructs.hpp"
#include "sensors/barometer/BarometerBase.hpp"
#include "sensors/distance/DistanceSimple.hpp"
#include "sensors/gps/GpsBase.hpp"
#include "sensors/imu/ImuBase.hpp"
#include "sensors/lidar/LidarSimple.hpp"
#include "sensors/magnetometer/MagnetometerBase.hpp"
#include "vehicles/car/api/CarApiBase.hpp"
#include "vehicles/multirotor/api/MultirotorApiBase.hpp"
#include "vehicles/multirotor/api/MultirotorCommon.hpp"

namespace airsim_ros {
namespace messages {

namespace helper_functions {

airsim_ros_pkgs::GPSYaw GetGpsMsgFromAirsimGeoPoint(
const msr::airlib::GeoPoint &geo_point);

msr::airlib::Quaternionr GetAirlibQuatFromRos(const tf2::Quaternion &tf2_quat);

nav_msgs::Odometry GetOdomMsgFromMultirotorState(
const msr::airlib::MultirotorState &drone_state, bool isEnu);

nav_msgs::Odometry GetOdomMsgFromTruthState(
const msr::airlib::Kinematics::State &truth_state, bool isEnu);

sensor_msgs::PointCloud2 GetLidarMsgFromAirsim(
const msr::airlib::LidarData &lidar_data, const std::string &vehicle_name,
bool isEnu);

airsim_ros_pkgs::Environment GetEnvironmentMsgFromAirsim(
const msr::airlib::Environment::State &env_data);

sensor_msgs::MagneticField GetMagMsgFromAirsim(
const msr::airlib::MagnetometerBase::Output &mag_data);

sensor_msgs::NavSatFix GetGpsMsgFromAirsim(
const msr::airlib::GpsBase::Output &gps_data);

sensor_msgs::Range GetRangeFromAirsim(
const msr::airlib::DistanceSensorData &dist_data);

airsim_ros_pkgs::Altimeter GetAltimeterMsgFromAirsim(
const msr::airlib::BarometerBase::Output &alt_data);

sensor_msgs::Imu GetImuMsgFromAirsim(
const msr::airlib::ImuBase::Output &imu_data);

} // namespace helper_functions

struct VelCmd {
double x;
double y;
Expand Down
21 changes: 0 additions & 21 deletions airsim_ros_pkgs/include/airsim_ros_pkgs/utils.hpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,6 @@
#ifndef AIRSIM_ROS_PKGS_INCLUDE_AIRSIM_ROS_PKGS_UTILS_HPP_
#define AIRSIM_ROS_PKGS_INCLUDE_AIRSIM_ROS_PKGS_UTILS_HPP_

#include "tf2/LinearMath/Quaternion.h"

#include "common/CommonStructs.hpp"

#include "airsim_ros_pkgs/messages.hpp"

namespace airsim_ros {
namespace utils {

Expand Down Expand Up @@ -58,21 +52,6 @@ inline T angular_dist(T from, T to) {
return d;
}

inline airsim_ros_pkgs::GPSYaw GetGpsMsgFromAirsimGeoPoint(
const msr::airlib::GeoPoint& geo_point) {
airsim_ros_pkgs::GPSYaw gps_msg;
gps_msg.latitude = geo_point.latitude;
gps_msg.longitude = geo_point.longitude;
gps_msg.altitude = geo_point.altitude;
return gps_msg;
}

inline msr::airlib::Quaternionr GetAirlibQuatFromRos(
const tf2::Quaternion& tf2_quat) {
return msr::airlib::Quaternionr(tf2_quat.w(), tf2_quat.x(), tf2_quat.y(),
tf2_quat.z());
}

} // namespace utils
} // namespace airsim_ros

Expand Down
6 changes: 4 additions & 2 deletions airsim_ros_pkgs/src/command_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ void CommandSubscriber::GimbalAngleQuatCommandCallback(
try {
tf2::convert(gimbal_angle_quat_cmd_msg->orientation, quaternion_command);
quaternion_command.normalize();
gimbal_cmd_.target_quat = utils::GetAirlibQuatFromRos(quaternion_command);
gimbal_cmd_.target_quat =
messages::helper_functions::GetAirlibQuatFromRos(quaternion_command);
gimbal_cmd_.camera_name = gimbal_angle_quat_cmd_msg->camera_name;
gimbal_cmd_.vehicle_name = gimbal_angle_quat_cmd_msg->vehicle_name;
has_gimbal_cmd_ = true;
Expand All @@ -48,7 +49,8 @@ void CommandSubscriber::GimbalAngleEulerCommandCallback(
utils::deg2rad(gimbal_angle_euler_cmd_msg->pitch),
utils::deg2rad(gimbal_angle_euler_cmd_msg->yaw));
quaternion_command.normalize();
gimbal_cmd_.target_quat = utils::GetAirlibQuatFromRos(quaternion_command);
gimbal_cmd_.target_quat =
messages::helper_functions::GetAirlibQuatFromRos(quaternion_command);
gimbal_cmd_.camera_name = gimbal_angle_euler_cmd_msg->camera_name;
gimbal_cmd_.vehicle_name = gimbal_angle_euler_cmd_msg->vehicle_name;
has_gimbal_cmd_ = true;
Expand Down
Loading