remove package not working

This commit is contained in:
Sem van der Hoeven
2023-04-19 10:04:22 +00:00
parent c9c2add7c7
commit f6b74583c7
9136 changed files with 562508 additions and 596632 deletions

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/include/px4_ros_com/frame_transforms.h

View File

@@ -0,0 +1,448 @@
/****************************************************************************
*
* 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 Functions to use on frame transforms
* @file frame_transform.h
* @addtogroup lib
* @author Nuno Marques <nuno.marques@dronesolutions.io>
*
* Adapted from MAVROS frame_tf.h
*/
#ifndef FRAME_TRANSFORMS_H
#define FRAME_TRANSFORMS_H
#include <Eigen/Eigen>
#include <Eigen/Geometry>
#include <array>
// for Covariance types
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/pose_with_covariance.hpp>
#include <geometry_msgs/msg/quaternion.hpp>
#include <geometry_msgs/msg/vector3.hpp>
#include <sensor_msgs/msg/imu.hpp>
namespace px4_ros_com
{
namespace frame_transforms
{
//! Type matching rosmsg for 3x3 covariance matrix
using Covariance3d = sensor_msgs::msg::Imu::_angular_velocity_covariance_type;
//! Type matching rosmsg for 6x6 covariance matrix
using Covariance6d = geometry_msgs::msg::PoseWithCovariance::_covariance_type;
//! Type matching rosmsg for 9x9 covariance matrix
using Covariance9d = std::array<double, 81>;
//! Eigen::Map for Covariance3d
using EigenMapCovariance3d = Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>>;
using EigenMapConstCovariance3d = Eigen::Map<const Eigen::Matrix<double, 3, 3, Eigen::RowMajor>>;
//! Eigen::Map for Covariance6d
using EigenMapCovariance6d = Eigen::Map<Eigen::Matrix<double, 6, 6, Eigen::RowMajor>>;
using EigenMapConstCovariance6d = Eigen::Map<const Eigen::Matrix<double, 6, 6, Eigen::RowMajor>>;
//! Eigen::Map for Covariance9d
using EigenMapCovariance9d = Eigen::Map<Eigen::Matrix<double, 9, 9, Eigen::RowMajor>>;
using EigenMapConstCovariance9d = Eigen::Map<const Eigen::Matrix<double, 9, 9, Eigen::RowMajor>>;
/**
* @brief Orientation transform options when applying rotations to data
*/
enum class StaticTF {
NED_TO_ENU, //!< change from expressed WRT NED frame to WRT ENU frame
ENU_TO_NED, //!< change from expressed WRT ENU frame to WRT NED frame
AIRCRAFT_TO_BASELINK, //!< change from expressed WRT aircraft frame to WRT to baselink frame
BASELINK_TO_AIRCRAFT, //!< change from expressed WRT baselnk to WRT aircraft
ECEF_TO_ENU, //!< change from expressed WRT ECEF frame to WRT ENU frame
ENU_TO_ECEF //!< change from expressed WRT ENU frame to WRT ECEF frame
};
// Utils to ease conversions
namespace utils
{
// Quaternion
namespace quaternion
{
/**
* @brief Convert euler angles to quaternion.
*/
Eigen::Quaterniond quaternion_from_euler(const Eigen::Vector3d &euler);
/**
* @brief Convert euler angles to quaternion.
*
* @return quaternion, same as @a tf::quaternionFromeuler() but in Eigen format.
*/
Eigen::Quaterniond quaternion_from_euler(const double roll, const double pitch, const double yaw);
/**
* @brief Convert quaternion to euler angles
* @return Eigen::Quaterniond
*/
Eigen::Vector3d quaternion_to_euler(const Eigen::Quaterniond &q);
/**
* @brief Convert quaternion to euler angles
*/
void quaternion_to_euler(const Eigen::Quaterniond &q, double &roll, double &pitch, double &yaw);
/**
* @brief Store Quaternion to float[4]
* Eigen::Quaterniond xyzw internal order to PX4 quaternion wxyz.
*/
void eigen_quat_to_array(const Eigen::Quaterniond &q, std::array<float, 4> &qarray);
/**
* @brief Convert float[4] quaternion to Eigen Quaternion
*/
Eigen::Quaterniond array_to_eigen_quat(const std::array<float, 4> &q);
/**
* @brief Get Yaw angle from quaternion
*/
double quaternion_get_yaw(const Eigen::Quaterniond &q);
} // namespace quaternion
// Data types
namespace types
{
/**
* @brief Convert covariance matrix to float[n]
*/
template <class T, std::size_t SIZE> void covariance_to_array(const T &cov, std::array<float, SIZE> &covmsg);
/**
* @brief Convert upper right triangular of a covariance matrix to float[n] array
*/
template <class T, std::size_t ARR_SIZE>
void covariance_urt_to_array(const T &covmap, std::array<float, ARR_SIZE> &covmsg);
/**
* @brief Convert float[n] array (upper right triangular of a covariance matrix)
* to Eigen::MatrixXd<n,n> full covariance matrix
*/
template <class T, std::size_t ARR_SIZE>
void array_urt_to_covariance_matrix(const std::array<float, ARR_SIZE> &covmsg, T &covmat);
} // namespace types
} // namespace utils
/**
* @brief Static quaternion needed for rotating between ENU and NED frames
* NED to ENU: +PI/2 rotation about Z (Down) followed by a +PI rotation around X (old North/new East)
* ENU to NED: +PI/2 rotation about Z (Up) followed by a +PI rotation about X (old East/new North)
*/
static const auto NED_ENU_Q = utils::quaternion::quaternion_from_euler(M_PI, 0.0, M_PI_2);
/**
* @brief Static quaternion needed for rotating between aircraft and base_link frames
* +PI rotation around X (Forward) axis transforms from Forward, Right, Down (aircraft)
* Fto Forward, Left, Up (base_link) frames.
*/
static const auto AIRCRAFT_BASELINK_Q = utils::quaternion::quaternion_from_euler(M_PI, 0.0, 0.0);
/**
* @brief Static vector needed for rotating between ENU and NED frames
* +PI rotation around X (North) axis follwed by +PI/2 rotation about Z (Down)
* gives the ENU frame. Similarly, a +PI rotation about X (East) followed by
* a +PI/2 roation about Z (Up) gives the NED frame.
*/
static const Eigen::Affine3d NED_ENU_AFFINE(NED_ENU_Q);
/**
* @brief Static vector needed for rotating between aircraft and base_link frames
* +PI rotation around X (Forward) axis transforms from Forward, Right, Down (aircraft)
* Fto Forward, Left, Up (base_link) frames.
*/
static const Eigen::Affine3d AIRCRAFT_BASELINK_AFFINE(AIRCRAFT_BASELINK_Q);
/**
* @brief 3-D matrices to fill 6-D rotation matrix applied to change covariance matrices coordinate frames
*/
static const auto NED_ENU_R = NED_ENU_Q.normalized().toRotationMatrix();
static const auto AIRCRAFT_BASELINK_R = AIRCRAFT_BASELINK_Q.normalized().toRotationMatrix();
/**
* @brief Use reflections instead of rotations for NED <-> ENU transformation
* to avoid NaN/Inf floating point pollution across different axes
* since in NED <-> ENU the axes are perfectly aligned.
*/
static const Eigen::PermutationMatrix<3> NED_ENU_REFLECTION_XY(Eigen::Vector3i(1, 0, 2));
static const Eigen::DiagonalMatrix<double, 3> NED_ENU_REFLECTION_Z(1, 1, -1);
/**
* @brief Auxiliar matrices to Covariance transforms
*/
using Matrix6d = Eigen::Matrix<double, 6, 6>;
using Matrix9d = Eigen::Matrix<double, 9, 9>;
/**
* @brief Transform representation of orientation from 1 frame to another.
* (e.g. transfrom orientation from representing from base_link -> NED to
* representing base_link -> ENU)
*/
Eigen::Quaterniond transform_orientation(const Eigen::Quaterniond &q, const StaticTF transform);
/**
* @brief Transform data expressed in one frame to another.
*/
Eigen::Vector3d transform_frame(const Eigen::Vector3d &vec, const Eigen::Quaterniond &q);
/**
* @brief Transform 3x3 convariance expressed in one frame to another.
*/
Covariance3d transform_frame(const Covariance3d &cov, const Eigen::Quaterniond &q);
/**
* @brief Transform 6x6 convariance expressed in one frame to another.
*/
Covariance6d transform_frame(const Covariance6d &cov, const Eigen::Quaterniond &q);
/**
* @brief Transform 9x9 convariance expressed in one frame to another.
*/
Covariance9d transform_frame(const Covariance9d &cov, const Eigen::Quaterniond &q);
/**
* @brief Transform data expressed in one frame to another.
*/
Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const StaticTF transform);
/**
* @brief Transform 3d convariance expressed in one frame to another.
*/
Covariance3d transform_static_frame(const Covariance3d &cov, const StaticTF transform);
/**
* @brief Transform 6d convariance expressed in one frame to another.
*/
Covariance6d transform_static_frame(const Covariance6d &cov, const StaticTF transform);
/**
* @brief Transform 9d convariance expressed in one frame to another
*/
Covariance9d transform_static_frame(const Covariance9d &cov, const StaticTF transform);
/**
* @brief Transform data expressed in one frame to another frame with additional
* map origin parameter.
*/
Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const Eigen::Vector3d &map_origin,
const StaticTF transform);
/**
* @brief Transform from orientation represented WRT NED frame to orientation
* represented WRT ENU frame
*/
template <class T> inline T ned_to_enu_orientation(const T &in)
{
return transform_orientation(in, StaticTF::NED_TO_ENU);
}
/**
* @brief Transform from orientation represented WRT ENU frame to orientation
* represented WRT NED frame
*/
template <class T> inline T enu_to_ned_orientation(const T &in)
{
return transform_orientation(in, StaticTF::ENU_TO_NED);
}
/**
* @brief Transform from orientation represented WRT aircraft body frame to
* orientation represented WRT base_link body frame
*/
template <class T> inline T aircraft_to_baselink_orientation(const T &in)
{
return transform_orientation(in, StaticTF::AIRCRAFT_TO_BASELINK);
}
/**
* @brief Transform from orientation represented WRT base_link body frame to
* orientation represented WRT aircraft body frame
*/
template <class T> inline T baselink_to_aircraft_orientation(const T &in)
{
return transform_orientation(in, StaticTF::BASELINK_TO_AIRCRAFT);
}
/**
* @brief Transform from orientation represented in PX4 format to ROS format
* PX4 format is aircraft to NED
* ROS format is baselink to ENU
*
* Two steps conversion:
* 1. aircraft to NED is converted to aircraft to ENU (NED_to_ENU conversion)
* 2. aircraft to ENU is converted to baselink to ENU (baselink_to_aircraft conversion)
*/
template <class T> inline T px4_to_ros_orientation(const T &in)
{
return baselink_to_aircraft_orientation(ned_to_enu_orientation(in));
}
/**
* @brief Transform from orientation represented in ROS format to PX4 format
* PX4 format is aircraft to NED
* ROS format is baselink to ENU
*
* Two steps conversion:
* 1. baselink to ENU is converted to baselink to NED (ENU_to_NED conversion)
* 2. baselink to NED is converted to aircraft to NED (aircraft_to_baselink conversion)
*/
template <class T> inline T ros_to_px4_orientation(const T &in)
{
return aircraft_to_baselink_orientation(enu_to_ned_orientation(in));
}
/**
* @brief Transform data expressed in NED to ENU local frame.
*/
template <class T> inline T ned_to_enu_local_frame(const T &in)
{
return transform_static_frame(in, StaticTF::NED_TO_ENU);
}
/**
* @brief Transform data expressed in ENU to NED frame.
*/
template <class T> inline T enu_to_ned_local_frame(const T &in)
{
return transform_static_frame(in, StaticTF::ENU_TO_NED);
}
/**
* @brief Transform data expressed in aircraft body frame to base_link body frame.
*/
template <class T> inline T aircraft_to_baselink_body_frame(const T &in)
{
return transform_static_frame(in, StaticTF::AIRCRAFT_TO_BASELINK);
}
/**
* @brief Transform data expressed in base_link body frame to aircraft body frame.
*/
template <class T> inline T baselink_to_aircraft_body_frame(const T &in)
{
return transform_static_frame(in, StaticTF::BASELINK_TO_AIRCRAFT);
}
/**
* @brief Transform data expressed in ECEF frame to ENU frame.
*
* @param in local ECEF coordinates [m]
* @param map_origin geodetic origin [lla]
* @returns local ENU coordinates [m].
*/
template <class T> inline T ecef_to_enu_local_frame(const T &in, const T &map_origin)
{
return transform_static_frame(in, map_origin, StaticTF::ECEF_TO_ENU);
}
/**
* @brief Transform data expressed in ENU frame to ECEF frame.
*
* @param in local ENU coordinates [m]
* @param map_origin geodetic origin [lla]
* @returns local ECEF coordinates [m].
*/
template <class T> inline T enu_to_ecef_local_frame(const T &in, const T &map_origin)
{
return transform_static_frame(in, map_origin, StaticTF::ENU_TO_ECEF);
}
/**
* @brief Transform data expressed in aircraft frame to NED frame.
* Assumes quaternion represents rotation from aircraft frame to NED frame.
*/
template <class T> inline T aircraft_to_ned_frame(const T &in, const Eigen::Quaterniond &q)
{
return transform_frame(in, q);
}
/**
* @brief Transform data expressed in NED to aircraft frame.
* Assumes quaternion represents rotation from NED to aircraft frame.
*/
template <class T> inline T ned_to_aircraft_frame(const T &in, const Eigen::Quaterniond &q)
{
return transform_frame(in, q);
}
/**
* @brief Transform data expressed in aircraft frame to ENU frame.
* Assumes quaternion represents rotation from aircraft frame to ENU frame.
*/
template <class T> inline T aircraft_to_enu_frame(const T &in, const Eigen::Quaterniond &q)
{
return transform_frame(in, q);
}
/**
* @brief Transform data expressed in ENU to aircraft frame.
* Assumes quaternion represents rotation from ENU to aircraft frame.
*/
template <class T> inline T enu_to_aircraft_frame(const T &in, const Eigen::Quaterniond &q)
{
return transform_frame(in, q);
}
/**
* @brief Transform data expressed in baselink to ENU frame.
* Assumes quaternion represents rotation from basel_link to ENU frame.
*/
template <class T> inline T baselink_to_enu_frame(const T &in, const Eigen::Quaterniond &q)
{
return transform_frame(in, q);
}
/**
* @brief Transform data expressed in ENU to base_link frame.
* Assumes quaternion represents rotation from ENU to base_link frame.
*/
template <class T> inline T enu_to_baselink_frame(const T &in, const Eigen::Quaterniond &q)
{
return transform_frame(in, q);
}
} // namespace frame_transforms
} // namespace px4_ros_com
#endif // FRAME_TRANSFORMS_H

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/debug_vect_advertiser

Binary file not shown.

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/offboard_control

Binary file not shown.

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/sensor_combined_listener

Binary file not shown.

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/vehicle_gps_position_listener

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_index/share/ament_index/resource_index/package_run_dependencies/px4_ros_com

View File

@@ -0,0 +1 @@
eigen;builtin_interfaces;rclcpp;px4_msgs;geometry_msgs;sensor_msgs;launch;launch_testing;launch_testing_ros;eigen3_cmake_module;rosidl_default_runtime;ros2launch;ament_lint_auto;ament_lint_common

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_index/share/ament_index/resource_index/packages/px4_ros_com

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_index/share/ament_index/resource_index/parent_prefix_path/px4_ros_com

View File

@@ -0,0 +1 @@
/home/ubuntu/ros2_ws/install/px4_ros_com:/home/ubuntu/ros2_ws/install/px4_msgs:/home/ubuntu/ros2_ws/install/drone_sensors:/home/ubuntu/ros2_ws/install/beacon_positioning:/opt/ros/foxy

View File

@@ -1 +1 @@
builtin_interfaces:eigen:eigen3_cmake_module:geometry_msgs:launch:launch_testing:launch_testing_ros:px4_msgs:rclcpp:rosidl_default_runtime:sensor_msgs
builtin_interfaces:eigen:eigen3_cmake_module:geometry_msgs:launch:launch_testing:launch_testing_ros:px4_msgs:rclcpp:ros2launch:rosidl_default_runtime:sensor_msgs

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/cmake/EnableC++XX.cmake

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/cmake/EnableSanitizers.cmake

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/cmake/GenerateMicroRTPSAgent.cmake

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_export_dependencies/ament_cmake_export_dependencies-extras.cmake

View File

@@ -0,0 +1,92 @@
# generated from ament_cmake_export_dependencies/cmake/ament_cmake_export_dependencies-extras.cmake.in
set(_exported_dependencies "ament_cmake;rclcpp;rosidl_default_runtime;eigen3_cmake_module;Eigen3;px4_msgs;geometry_msgs;sensor_msgs")
find_package(ament_cmake_libraries QUIET REQUIRED)
# find_package() all dependencies
# and append their DEFINITIONS INCLUDE_DIRS, LIBRARIES, and LINK_FLAGS
# variables to px4_ros_com_DEFINITIONS, px4_ros_com_INCLUDE_DIRS,
# px4_ros_com_LIBRARIES, and px4_ros_com_LINK_FLAGS.
# Additionally collect the direct dependency names in
# px4_ros_com_DEPENDENCIES as well as the recursive dependency names
# in px4_ros_com_RECURSIVE_DEPENDENCIES.
if(NOT _exported_dependencies STREQUAL "")
find_package(ament_cmake_core QUIET REQUIRED)
set(px4_ros_com_DEPENDENCIES ${_exported_dependencies})
set(px4_ros_com_RECURSIVE_DEPENDENCIES ${_exported_dependencies})
set(_libraries)
foreach(_dep ${_exported_dependencies})
if(NOT ${_dep}_FOUND)
find_package("${_dep}" QUIET REQUIRED)
endif()
# if a package provides modern CMake interface targets use them
# exclusively assuming the classic CMake variables only exist for
# backward compatibility
set(use_modern_cmake FALSE)
if(NOT "${${_dep}_TARGETS}" STREQUAL "")
foreach(_target ${${_dep}_TARGETS})
# only use actual targets
# in case a package uses this variable for other content
if(TARGET "${_target}")
get_target_property(_include_dirs ${_target} INTERFACE_INCLUDE_DIRECTORIES)
if(_include_dirs)
list_append_unique(px4_ros_com_INCLUDE_DIRS "${_include_dirs}")
endif()
get_target_property(_imported_configurations ${_target} IMPORTED_CONFIGURATIONS)
if(_imported_configurations)
string(TOUPPER "${_imported_configurations}" _imported_configurations)
if(DEBUG_CONFIGURATIONS)
string(TOUPPER "${DEBUG_CONFIGURATIONS}" _debug_configurations_uppercase)
else()
set(_debug_configurations_uppercase "DEBUG")
endif()
foreach(_imported_config ${_imported_configurations})
get_target_property(_imported_implib ${_target} IMPORTED_IMPLIB_${_imported_config})
if(_imported_implib)
set(_imported_implib_config "optimized")
if(${_imported_config} IN_LIST _debug_configurations_uppercase)
set(_imported_implib_config "debug")
endif()
list(APPEND _libraries ${_imported_implib_config} ${_imported_implib})
else()
get_target_property(_imported_location ${_target} IMPORTED_LOCATION_${_imported_config})
if(_imported_location)
list(APPEND _libraries "${_imported_location}")
endif()
endif()
endforeach()
endif()
get_target_property(_link_libraries ${_target} INTERFACE_LINK_LIBRARIES)
if(_link_libraries)
list(APPEND _libraries "${_link_libraries}")
endif()
set(use_modern_cmake TRUE)
endif()
endforeach()
endif()
if(NOT use_modern_cmake)
if(${_dep}_DEFINITIONS)
list_append_unique(px4_ros_com_DEFINITIONS "${${_dep}_DEFINITIONS}")
endif()
if(${_dep}_INCLUDE_DIRS)
list_append_unique(px4_ros_com_INCLUDE_DIRS "${${_dep}_INCLUDE_DIRS}")
endif()
if(${_dep}_LIBRARIES)
list(APPEND _libraries "${${_dep}_LIBRARIES}")
endif()
if(${_dep}_LINK_FLAGS)
list_append_unique(px4_ros_com_LINK_FLAGS "${${_dep}_LINK_FLAGS}")
endif()
if(${_dep}_RECURSIVE_DEPENDENCIES)
list_append_unique(px4_ros_com_RECURSIVE_DEPENDENCIES "${${_dep}_RECURSIVE_DEPENDENCIES}")
endif()
endif()
if(_libraries)
ament_libraries_deduplicate(_libraries "${_libraries}")
list(APPEND px4_ros_com_LIBRARIES "${_libraries}")
endif()
endforeach()
endif()

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_export_include_directories/ament_cmake_export_include_directories-extras.cmake

View File

@@ -0,0 +1,16 @@
# generated from ament_cmake_export_include_directories/cmake/ament_cmake_export_include_directories-extras.cmake.in
set(_exported_include_dirs "${px4_ros_com_DIR}/../../../include")
# append include directories to px4_ros_com_INCLUDE_DIRS
# warn about not existing paths
if(NOT _exported_include_dirs STREQUAL "")
find_package(ament_cmake_core QUIET REQUIRED)
foreach(_exported_include_dir ${_exported_include_dirs})
if(NOT IS_DIRECTORY "${_exported_include_dir}")
message(WARNING "Package 'px4_ros_com' exports the include directory '${_exported_include_dir}' which doesn't exist")
endif()
normalize_path(_exported_include_dir "${_exported_include_dir}")
list(APPEND px4_ros_com_INCLUDE_DIRS "${_exported_include_dir}")
endforeach()
endif()

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_export_libraries/ament_cmake_export_libraries-extras.cmake

View File

@@ -0,0 +1,140 @@
# generated from ament_cmake_export_libraries/cmake/template/ament_cmake_export_libraries.cmake.in
set(_exported_libraries "frame_transforms")
set(_exported_library_names "")
# populate px4_ros_com_LIBRARIES
if(NOT _exported_libraries STREQUAL "")
# loop over libraries, either target names or absolute paths
list(LENGTH _exported_libraries _length)
set(_i 0)
while(_i LESS _length)
list(GET _exported_libraries ${_i} _arg)
# pass linker flags along
if("${_arg}" MATCHES "^-" AND NOT "${_arg}" MATCHES "^-[l|framework]")
list(APPEND px4_ros_com_LIBRARIES "${_arg}")
math(EXPR _i "${_i} + 1")
continue()
endif()
if("${_arg}" MATCHES "^(debug|optimized|general)$")
# remember build configuration keyword
# and get following library
set(_cfg "${_arg}")
math(EXPR _i "${_i} + 1")
if(_i EQUAL _length)
message(FATAL_ERROR "Package 'px4_ros_com' passes the build configuration keyword '${_cfg}' as the last exported library")
endif()
list(GET _exported_libraries ${_i} _library)
else()
# the value is a library without a build configuration keyword
set(_cfg "")
set(_library "${_arg}")
endif()
math(EXPR _i "${_i} + 1")
if(NOT IS_ABSOLUTE "${_library}")
# search for library target relative to this CMake file
set(_lib "NOTFOUND")
find_library(
_lib NAMES "${_library}"
PATHS "${px4_ros_com_DIR}/../../../lib"
NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH
)
if(NOT _lib)
# warn about not existing library and ignore it
message(FATAL_ERROR "Package 'px4_ros_com' exports the library '${_library}' which couldn't be found")
elseif(NOT IS_ABSOLUTE "${_lib}")
# the found library must be an absolute path
message(FATAL_ERROR "Package 'px4_ros_com' found the library '${_library}' at '${_lib}' which is not an absolute path")
elseif(NOT EXISTS "${_lib}")
# the found library must exist
message(FATAL_ERROR "Package 'px4_ros_com' found the library '${_lib}' which doesn't exist")
else()
list(APPEND px4_ros_com_LIBRARIES ${_cfg} "${_lib}")
endif()
else()
if(NOT EXISTS "${_library}")
# the found library must exist
message(WARNING "Package 'px4_ros_com' exports the library '${_library}' which doesn't exist")
else()
list(APPEND px4_ros_com_LIBRARIES ${_cfg} "${_library}")
endif()
endif()
endwhile()
endif()
# find_library() library names with optional LIBRARY_DIRS
# and add the libraries to px4_ros_com_LIBRARIES
if(NOT _exported_library_names STREQUAL "")
# loop over library names
# but remember related build configuration keyword if available
list(LENGTH _exported_library_names _length)
set(_i 0)
while(_i LESS _length)
list(GET _exported_library_names ${_i} _arg)
# pass linker flags along
if("${_arg}" MATCHES "^-" AND NOT "${_arg}" MATCHES "^-[l|framework]")
list(APPEND px4_ros_com_LIBRARIES "${_arg}")
math(EXPR _i "${_i} + 1")
continue()
endif()
if("${_arg}" MATCHES "^(debug|optimized|general)$")
# remember build configuration keyword
# and get following library name
set(_cfg "${_arg}")
math(EXPR _i "${_i} + 1")
if(_i EQUAL _length)
message(FATAL_ERROR "Package 'px4_ros_com' passes the build configuration keyword '${_cfg}' as the last exported target")
endif()
list(GET _exported_library_names ${_i} _library)
else()
# the value is a library target without a build configuration keyword
set(_cfg "")
set(_library "${_arg}")
endif()
math(EXPR _i "${_i} + 1")
# extract optional LIBRARY_DIRS from library name
string(REPLACE ":" ";" _library_dirs "${_library}")
list(GET _library_dirs 0 _library_name)
list(REMOVE_AT _library_dirs 0)
set(_lib "NOTFOUND")
if(NOT _library_dirs)
# search for library in the common locations
find_library(
_lib
NAMES "${_library_name}"
)
if(NOT _lib)
# warn about not existing library and later ignore it
message(WARNING "Package 'px4_ros_com' exports library '${_library_name}' which couldn't be found")
endif()
else()
# search for library in the specified directories
find_library(
_lib
NAMES "${_library_name}"
PATHS ${_library_dirs}
NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH
)
if(NOT _lib)
# warn about not existing library and later ignore it
message(WARNING "Package 'px4_ros_com' exports library '${_library_name}' with LIBRARY_DIRS '${_library_dirs}' which couldn't be found")
endif()
endif()
if(_lib)
list(APPEND px4_ros_com_LIBRARIES ${_cfg} "${_lib}")
endif()
endwhile()
endif()
# TODO(dirk-thomas) deduplicate px4_ros_com_LIBRARIES
# while maintaining library order
# as well as build configuration keywords
# as well as linker flags

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_export_targets/ament_cmake_export_targets-extras.cmake

View File

@@ -0,0 +1,27 @@
# generated from ament_cmake_export_targets/cmake/ament_cmake_export_targets-extras.cmake.in
set(_exported_targets "export_frame_transforms")
# include all exported targets
if(NOT _exported_targets STREQUAL "")
foreach(_target ${_exported_targets})
set(_export_file "${px4_ros_com_DIR}/${_target}Export.cmake")
include("${_export_file}")
# extract the target names associated with the export
set(_regex "foreach\\((_cmake)?_expected_?[Tt]arget (IN ITEMS )?(.+)\\)")
file(
STRINGS "${_export_file}" _foreach_targets
REGEX "${_regex}")
list(LENGTH _foreach_targets _matches)
if(NOT _matches EQUAL 1)
message(FATAL_ERROR
"Failed to find exported target names in '${_export_file}'")
endif()
string(REGEX REPLACE "${_regex}" "\\3" _targets "${_foreach_targets}")
string(REPLACE " " ";" _targets "${_targets}")
list(LENGTH _targets _length)
list(APPEND px4_ros_com_TARGETS ${_targets})
endforeach()
endif()

View File

@@ -1,15 +1,15 @@
#----------------------------------------------------------------
# Generated CMake target import file for configuration "RELWITHDEBINFO".
# Generated CMake target import file.
#----------------------------------------------------------------
# Commands may need to know the format version.
set(CMAKE_IMPORT_FILE_VERSION 1)
# Import target "px4_ros_com::frame_transforms" for configuration "RELWITHDEBINFO"
set_property(TARGET px4_ros_com::frame_transforms APPEND PROPERTY IMPORTED_CONFIGURATIONS RELWITHDEBINFO)
# Import target "px4_ros_com::frame_transforms" for configuration ""
set_property(TARGET px4_ros_com::frame_transforms APPEND PROPERTY IMPORTED_CONFIGURATIONS NOCONFIG)
set_target_properties(px4_ros_com::frame_transforms PROPERTIES
IMPORTED_LOCATION_RELWITHDEBINFO "${_IMPORT_PREFIX}/lib/libframe_transforms.so"
IMPORTED_SONAME_RELWITHDEBINFO "libframe_transforms.so"
IMPORTED_LOCATION_NOCONFIG "${_IMPORT_PREFIX}/lib/libframe_transforms.so"
IMPORTED_SONAME_NOCONFIG "libframe_transforms.so"
)
list(APPEND _IMPORT_CHECK_TARGETS px4_ros_com::frame_transforms )

File diff suppressed because one or more lines are too long

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_core/px4_ros_comConfig-version.cmake

View File

@@ -0,0 +1,14 @@
# generated from ament/cmake/core/templates/nameConfig-version.cmake.in
set(PACKAGE_VERSION "0.1.0")
set(PACKAGE_VERSION_EXACT False)
set(PACKAGE_VERSION_COMPATIBLE False)
if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}")
set(PACKAGE_VERSION_EXACT True)
set(PACKAGE_VERSION_COMPATIBLE True)
endif()
if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}")
set(PACKAGE_VERSION_COMPATIBLE True)
endif()

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_core/px4_ros_comConfig.cmake

View File

@@ -0,0 +1,42 @@
# generated from ament/cmake/core/templates/nameConfig.cmake.in
# prevent multiple inclusion
if(_px4_ros_com_CONFIG_INCLUDED)
# ensure to keep the found flag the same
if(NOT DEFINED px4_ros_com_FOUND)
# explicitly set it to FALSE, otherwise CMake will set it to TRUE
set(px4_ros_com_FOUND FALSE)
elseif(NOT px4_ros_com_FOUND)
# use separate condition to avoid uninitialized variable warning
set(px4_ros_com_FOUND FALSE)
endif()
return()
endif()
set(_px4_ros_com_CONFIG_INCLUDED TRUE)
# output package information
if(NOT px4_ros_com_FIND_QUIETLY)
message(STATUS "Found px4_ros_com: 0.1.0 (${px4_ros_com_DIR})")
endif()
# warn when using a deprecated package
if(NOT "" STREQUAL "")
set(_msg "Package 'px4_ros_com' is deprecated")
# append custom deprecation text if available
if(NOT "" STREQUAL "TRUE")
set(_msg "${_msg} ()")
endif()
# optionally quiet the deprecation message
if(NOT ${px4_ros_com_DEPRECATED_QUIET})
message(DEPRECATION "${_msg}")
endif()
endif()
# flag package as ament-based to distinguish it after being find_package()-ed
set(px4_ros_com_FOUND_AMENT_PACKAGE TRUE)
# include all config extra files
set(_extras "ament_cmake_export_dependencies-extras.cmake;ament_cmake_export_targets-extras.cmake;ament_cmake_export_include_directories-extras.cmake;ament_cmake_export_libraries-extras.cmake")
foreach(_extra ${_extras})
include("${px4_ros_com_DIR}/${_extra}")
endforeach()

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_environment_hooks/ament_prefix_path.dsv

View File

@@ -0,0 +1 @@
prepend-non-duplicate;AMENT_PREFIX_PATH;

View File

@@ -1 +0,0 @@
/opt/ros/foxy/share/ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh

View File

@@ -0,0 +1,4 @@
# copied from
# ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh
ament_prepend_unique_value AMENT_PREFIX_PATH "$AMENT_CURRENT_PREFIX"

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_environment_hooks/library_path.dsv

View File

@@ -0,0 +1 @@
prepend-non-duplicate;LD_LIBRARY_PATH;lib

View File

@@ -1 +0,0 @@
/opt/ros/foxy/lib/python3.8/site-packages/ament_package/template/environment_hook/library_path.sh

View File

@@ -0,0 +1,16 @@
# copied from ament_package/template/environment_hook/library_path.sh
# detect if running on Darwin platform
_UNAME=`uname -s`
_IS_DARWIN=0
if [ "$_UNAME" = "Darwin" ]; then
_IS_DARWIN=1
fi
unset _UNAME
if [ $_IS_DARWIN -eq 0 ]; then
ament_prepend_unique_value LD_LIBRARY_PATH "$AMENT_CURRENT_PREFIX/lib"
else
ament_prepend_unique_value DYLD_LIBRARY_PATH "$AMENT_CURRENT_PREFIX/lib"
fi
unset _IS_DARWIN

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_environment_hooks/path.dsv

View File

@@ -0,0 +1 @@
prepend-non-duplicate-if-exists;PATH;bin

View File

@@ -1 +0,0 @@
/opt/ros/foxy/share/ament_cmake_core/cmake/environment_hooks/environment/path.sh

View File

@@ -0,0 +1,5 @@
# copied from ament_cmake_core/cmake/environment_hooks/environment/path.sh
if [ -d "$AMENT_CURRENT_PREFIX/bin" ]; then
ament_prepend_unique_value PATH "$AMENT_CURRENT_PREFIX/bin"
fi

View File

@@ -1 +0,0 @@
prepend-non-duplicate;PATH;bin

View File

@@ -1,3 +0,0 @@
# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
colcon_prepend_unique_value PATH "$env:COLCON_CURRENT_PREFIX\bin"

View File

@@ -1,3 +0,0 @@
# generated from colcon_core/shell/template/hook_prepend_value.sh.em
_colcon_prepend_unique_value PATH "$COLCON_CURRENT_PREFIX/bin"

View File

@@ -1 +0,0 @@
prepend-non-duplicate;PATH;bin

View File

@@ -1,3 +0,0 @@
# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
colcon_prepend_unique_value PATH "$env:COLCON_CURRENT_PREFIX\bin"

View File

@@ -1,3 +0,0 @@
# generated from colcon_core/shell/template/hook_prepend_value.sh.em
_colcon_prepend_unique_value PATH "$COLCON_CURRENT_PREFIX/bin"

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/launch/offboard_control_launch.yaml

View File

@@ -0,0 +1,7 @@
launch:
- node:
pkg: "px4_ros_com"
exec: "offboard_control"
name: "offboard_control"
output: "screen"

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/launch/sensor_combined_listener.launch.py

View File

@@ -0,0 +1,62 @@
#!/usr/bin/env python
################################################################################
#
# Copyright (c) 2018-2022, 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.
#
################################################################################
"""
Example to launch a sensor_combined listener node.
"""
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import ExecuteProcess
def generate_launch_description():
micro_ros_agent = ExecuteProcess(
cmd=[[
'micro-ros-agent udp4 --port 8888 -v '
]],
shell=True
)
sensor_combined_listener_node = Node(
package='px4_ros_com',
executable='sensor_combined_listener',
output='screen',
shell=True,
)
return LaunchDescription([
#micro_ros_agent,
sensor_combined_listener_node
])

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_environment_hooks/local_setup.bash

View File

@@ -0,0 +1,46 @@
# generated from ament_package/template/package_level/local_setup.bash.in
# source local_setup.sh from same directory as this file
_this_path=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" && pwd)
# provide AMENT_CURRENT_PREFIX to shell script
AMENT_CURRENT_PREFIX=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." && pwd)
# store AMENT_CURRENT_PREFIX to restore it before each environment hook
_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX
# trace output
if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then
echo "# . \"$_this_path/local_setup.sh\""
fi
. "$_this_path/local_setup.sh"
unset _this_path
# unset AMENT_ENVIRONMENT_HOOKS
# if not appending to them for return
if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then
unset AMENT_ENVIRONMENT_HOOKS
fi
# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks
AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX
# list all environment hooks of this package
# source all shell-specific environment hooks of this package
# if not returning them
if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then
_package_local_setup_IFS=$IFS
IFS=":"
for _hook in $AMENT_ENVIRONMENT_HOOKS; do
# restore AMENT_CURRENT_PREFIX for each environment hook
AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX
# restore IFS before sourcing other files
IFS=$_package_local_setup_IFS
. "$_hook"
done
unset _hook
IFS=$_package_local_setup_IFS
unset _package_local_setup_IFS
unset AMENT_ENVIRONMENT_HOOKS
fi
unset _package_local_setup_AMENT_CURRENT_PREFIX
unset AMENT_CURRENT_PREFIX

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_environment_hooks/local_setup.dsv

View File

@@ -0,0 +1,3 @@
source;share/px4_ros_com/environment/ament_prefix_path.sh
source;share/px4_ros_com/environment/library_path.sh
source;share/px4_ros_com/environment/path.sh

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_environment_hooks/local_setup.sh

View File

@@ -0,0 +1,134 @@
# generated from ament_package/template/package_level/local_setup.sh.in
# since this file is sourced use either the provided AMENT_CURRENT_PREFIX
# or fall back to the destination set at configure time
: ${AMENT_CURRENT_PREFIX:="/home/ubuntu/ros2_ws/install/px4_ros_com"}
if [ ! -d "$AMENT_CURRENT_PREFIX" ]; then
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
echo "The compile time prefix path '$AMENT_CURRENT_PREFIX' doesn't " \
"exist. Consider sourcing a different extension than '.sh'." 1>&2
else
AMENT_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
fi
fi
# function to append values to environment variables
# using colons as separators and avoiding leading separators
ament_append_value() {
# arguments
_listname="$1"
_value="$2"
#echo "listname $_listname"
#eval echo "list value \$$_listname"
#echo "value $_value"
# avoid leading separator
eval _values=\"\$$_listname\"
if [ -z "$_values" ]; then
eval export $_listname=\"$_value\"
#eval echo "set list \$$_listname"
else
# field separator must not be a colon
_ament_append_value_IFS=$IFS
unset IFS
eval export $_listname=\"\$$_listname:$_value\"
#eval echo "append list \$$_listname"
IFS=$_ament_append_value_IFS
unset _ament_append_value_IFS
fi
unset _values
unset _value
unset _listname
}
# function to prepend non-duplicate values to environment variables
# using colons as separators and avoiding trailing separators
ament_prepend_unique_value() {
# arguments
_listname="$1"
_value="$2"
#echo "listname $_listname"
#eval echo "list value \$$_listname"
#echo "value $_value"
# check if the list contains the value
eval _values=\"\$$_listname\"
_duplicate=
_ament_prepend_unique_value_IFS=$IFS
IFS=":"
if [ "$AMENT_SHELL" = "zsh" ]; then
ament_zsh_to_array _values
fi
for _item in $_values; do
# ignore empty strings
if [ -z "$_item" ]; then
continue
fi
if [ "$_item" = "$_value" ]; then
_duplicate=1
fi
done
unset _item
# prepend only non-duplicates
if [ -z "$_duplicate" ]; then
# avoid trailing separator
if [ -z "$_values" ]; then
eval export $_listname=\"$_value\"
#eval echo "set list \$$_listname"
else
# field separator must not be a colon
unset IFS
eval export $_listname=\"$_value:\$$_listname\"
#eval echo "prepend list \$$_listname"
fi
fi
IFS=$_ament_prepend_unique_value_IFS
unset _ament_prepend_unique_value_IFS
unset _duplicate
unset _values
unset _value
unset _listname
}
# unset AMENT_ENVIRONMENT_HOOKS
# if not appending to them for return
if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then
unset AMENT_ENVIRONMENT_HOOKS
fi
# list all environment hooks of this package
ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/px4_ros_com/environment/ament_prefix_path.sh"
ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/px4_ros_com/environment/library_path.sh"
ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/px4_ros_com/environment/path.sh"
# source all shell-specific environment hooks of this package
# if not returning them
if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then
_package_local_setup_IFS=$IFS
IFS=":"
if [ "$AMENT_SHELL" = "zsh" ]; then
ament_zsh_to_array AMENT_ENVIRONMENT_HOOKS
fi
for _hook in $AMENT_ENVIRONMENT_HOOKS; do
if [ -f "$_hook" ]; then
# restore IFS before sourcing other files
IFS=$_package_local_setup_IFS
# trace output
if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then
echo "# . \"$_hook\""
fi
. "$_hook"
fi
done
unset _hook
IFS=$_package_local_setup_IFS
unset _package_local_setup_IFS
unset AMENT_ENVIRONMENT_HOOKS
fi
# reset AMENT_CURRENT_PREFIX after each package
# allowing to source multiple package-level setup files
unset AMENT_CURRENT_PREFIX

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/build/px4_ros_com/ament_cmake_environment_hooks/local_setup.zsh

View File

@@ -0,0 +1,59 @@
# generated from ament_package/template/package_level/local_setup.zsh.in
AMENT_SHELL=zsh
# source local_setup.sh from same directory as this file
_this_path=$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)
# provide AMENT_CURRENT_PREFIX to shell script
AMENT_CURRENT_PREFIX=$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)
# store AMENT_CURRENT_PREFIX to restore it before each environment hook
_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX
# function to convert array-like strings into arrays
# to wordaround SH_WORD_SPLIT not being set
ament_zsh_to_array() {
local _listname=$1
local _dollar="$"
local _split="{="
local _to_array="(\"$_dollar$_split$_listname}\")"
eval $_listname=$_to_array
}
# trace output
if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then
echo "# . \"$_this_path/local_setup.sh\""
fi
# the package-level local_setup file unsets AMENT_CURRENT_PREFIX
. "$_this_path/local_setup.sh"
unset _this_path
# unset AMENT_ENVIRONMENT_HOOKS
# if not appending to them for return
if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then
unset AMENT_ENVIRONMENT_HOOKS
fi
# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks
AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX
# list all environment hooks of this package
# source all shell-specific environment hooks of this package
# if not returning them
if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then
_package_local_setup_IFS=$IFS
IFS=":"
for _hook in $AMENT_ENVIRONMENT_HOOKS; do
# restore AMENT_CURRENT_PREFIX for each environment hook
AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX
# restore IFS before sourcing other files
IFS=$_package_local_setup_IFS
. "$_hook"
done
unset _hook
IFS=$_package_local_setup_IFS
unset _package_local_setup_IFS
unset AMENT_ENVIRONMENT_HOOKS
fi
unset _package_local_setup_AMENT_CURRENT_PREFIX
unset AMENT_CURRENT_PREFIX

View File

@@ -4,12 +4,6 @@ source;share/px4_ros_com/hook/cmake_prefix_path.sh
source;share/px4_ros_com/hook/ld_library_path_lib.ps1
source;share/px4_ros_com/hook/ld_library_path_lib.dsv
source;share/px4_ros_com/hook/ld_library_path_lib.sh
source;share/px4_ros_com/hook/path.ps1
source;share/px4_ros_com/hook/path.dsv
source;share/px4_ros_com/hook/path.sh
source;share/px4_ros_com/hook/pythonscriptspath.ps1
source;share/px4_ros_com/hook/pythonscriptspath.dsv
source;share/px4_ros_com/hook/pythonscriptspath.sh
source;share/px4_ros_com/local_setup.bash
source;share/px4_ros_com/local_setup.dsv
source;share/px4_ros_com/local_setup.ps1

View File

@@ -112,8 +112,6 @@ $env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.Ful
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/px4_ros_com/hook/cmake_prefix_path.ps1"
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/px4_ros_com/hook/ld_library_path_lib.ps1"
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/px4_ros_com/hook/path.ps1"
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/px4_ros_com/hook/pythonscriptspath.ps1"
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/px4_ros_com/local_setup.ps1"
Remove-Item Env:\COLCON_CURRENT_PREFIX

View File

@@ -80,8 +80,6 @@ _colcon_package_sh_source_script() {
# source sh hooks
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/px4_ros_com/hook/cmake_prefix_path.sh"
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/px4_ros_com/hook/ld_library_path_lib.sh"
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/px4_ros_com/hook/path.sh"
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/px4_ros_com/hook/pythonscriptspath.sh"
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/px4_ros_com/local_setup.sh"
unset _colcon_package_sh_source_script

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/package.xml

View File

@@ -0,0 +1,42 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>px4_ros_com</name>
<version>0.1.0</version>
<description>Package to interface ROS 2 with PX4</description>
<maintainer email="nuno.marques@dronesolutions.io">Nuno Marques</maintainer>
<author email="nuno.marques@dronesolutions.io">Nuno Marques</author>
<license>BSD 3-Clause</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>
<build_depend>eigen</build_depend>
<build_depend>ros_environment</build_depend>
<depend>builtin_interfaces</depend>
<depend>rclcpp</depend>
<depend>px4_msgs</depend>
<depend>geometry_msgs</depend>
<depend>sensor_msgs</depend>
<depend>launch</depend>
<depend>launch_testing</depend>
<depend>launch_testing_ros</depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<exec_depend>ros2launch</exec_depend>
<buildtool_export_depend>eigen3_cmake_module</buildtool_export_depend>
<build_export_depend>eigen</build_export_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/test/__init__.py

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/test/pipeline_io_test.py

View File

@@ -0,0 +1,167 @@
#!/usr/bin/env python3
################################################################################
#
# Copyright 2019 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.
#
################################################################################
# This script launches the microRTPS bridge pipeline to verify if there is
# data being exchanged between the flight controller (in SITL) and companion
# computer side, with its DDS participants
import argparse
import os
from time import sleep
from sys import exit
from subprocess import call, CalledProcessError, check_output, DEVNULL, Popen, STDOUT
if __name__ == "__main__":
default_px4_ros_com_install_dir = os.path.expanduser("~") + "/PX4/px4_ros2_ws/install"
default_px4_dir = os.path.expanduser("~") + "/PX4/Firmware"
default_px4_target = "iris_rtps"
default_test_dir = os.path.dirname(os.path.realpath(__file__))
default_test_type = "fcu_output"
default_subscriber_topic = "sensor_combined"
default_publisher_topic = "debug_vect"
parser = argparse.ArgumentParser()
parser.add_argument("-d", "--test-dir", dest='test_dir', type=str,
help="Absolute path to test script", default=default_test_dir)
parser.add_argument("-f", "--px4-firmware-dir", dest='px4_dir', type=str,
help="Absolute path to PX4 Firmware dir, defaults to $HOME/PX4/Firmware", default=default_px4_dir)
parser.add_argument("-b", "--px4-build-target", dest='px4_target', type=str,
help="PX4 SITL target, defaults to iris_rtps", default=default_px4_target)
parser.add_argument("-t", "--test-type", dest='test_type', type=str,
help="Test type [fcu_input, fcu_output], defaults to 'fcu_output'", default=default_test_type)
parser.add_argument("-s", "--subscriber", dest='subscriber_topic', type=str,
help="ROS2 topic to test, defaults to 'sensor_combined'", default=default_subscriber_topic)
parser.add_argument("-p", "--publisher", dest='publisher_topic', type=str,
help="ROS2 publisher data, meaning the data to be received on the flight controller side, defaults to 'debug_vect'", default=default_publisher_topic)
# Parse arguments
args = parser.parse_args()
if os.path.isabs(args.px4_dir):
px4_dir = args.px4_dir
else:
raise Exception("Please provide PX4 Firmware absolute path")
px4_target = args.px4_target
test_dir = args.test_dir
test_type = args.test_type
listener = args.subscriber_topic
advertiser = args.publisher_topic
# get ROS distro
ros_distro = check_output("rosversion -d", shell=True)
# get PX4 Firmware tag
px4_tag = check_output(
"cd " + px4_dir + " && git describe --abbrev=0 && cd " + os.getcwd(), shell=True)
print(
"\n\033[34m-------------- PX4 XRCE-DDS COMMUNICATION TEST --------------\033[0m")
print("\n-- Test configuration:\n")
print(" > ROS 2 distro: \033[36m" +
str(ros_distro.strip().decode("utf-8")).capitalize() + "\033[0m")
print(" > PX4 Firmware: \033[36m" + px4_tag.decode() + "\033[0m")
print("\033[5m-- Running " + ("Output test" if(test_type ==
"fcu_output") else "Input test") + "...\033[0m")
# launch the micro-ros-agent
print("\n\033[93m-- Starting micro-ros-agent..." + "\033[0m\n")
call("micro-ros-agent udp4 --port 2019 &", shell=True, stderr=STDOUT)
# waits for the agent to load
sleep(3)
# launch PX4 SITL daemon, in headless mode
print(
"\n\033[93m-- Starting the PX4 SITL daemon and Gazebo (without GUI)...\033[0m\n")
call("cd " + px4_dir + " && (NO_PXH=1 HEADLESS=1 make px4_sitl_default gazebo_" +
px4_target + " &) && cd " + os.getcwd(), shell=True, stderr=DEVNULL)
# waits for PX4 daemon and Gazebo to load
sleep(20)
# setup the PX4 SITL bin dir
px4_bin_dir = os.path.join(px4_dir, "build/px4_sitl_default/bin")
# launch the specified test
topic = ""
test_format = list()
test_result = -1
if(test_type == "fcu_output"):
# Flight controller output tests
if (listener == "sensor_combined"):
node = "sensor_combined_listener"
topic = "sensor_combined"
test_format = ["output", "from"]
test_result = call(
"python3 " + test_dir + "/test_output.py -t " + topic.replace("_", " ").title().replace(" ", ""), stderr=STDOUT, shell=True,
universal_newlines=True)
elif(test_type == "fcu_input"):
# Flight controller input tests
if (advertiser == "debug_vect"):
package_name = "px4_ros_com"
node = "debug_vect_advertiser"
topic = "debug_vect"
test_format = ["input", "on"]
test_result = call(
"python3 " + test_dir + "/test_input.py -b " + px4_bin_dir + " -p " + package_name + " -n " + node + " -t " + topic, stderr=STDOUT, shell=True,
universal_newlines=True)
elif (advertiser == "onboard_computer_status"):
# specific test for https://github.com/Auterion/system_monitor_ros
package_name = "system_monitor_ros"
node = "system_monitor_node"
topic = "onboard_computer_status"
test_format = ["input", "on"]
test_result = call(
"python3 " + test_dir + "/test_input.py -b " + px4_bin_dir + " -p " + package_name + " -n " + node + " -t " + topic, stderr=STDOUT, shell=True,
universal_newlines=True)
call("killall gzserver micro-ros-agent px4 ros2",
shell=True, stdout=DEVNULL, stderr=DEVNULL)
print(
"\033[34m------------------------ TEST RESULTS ------------------------\033[0m")
if (test_result):
print("\033[91m" + ("Output test" if(test_type == "fcu_output") else "Input test") + ": [FAILED]\tFlight controller " + test_format[0] + " test failed! Failed to get data " + test_format[1] + " the '" +
topic + "' uORB topic\033[0m")
print(
"\033[34m" + "--------------------------------------------------------------" + "\033[0m\n")
exit(1)
else:
print("\033[92m" + ("Output test" if(test_type == "fcu_output") else "Input test") + ": [SUCCESS]\tFlight controller " + test_format[0] + " test successfull! Successfully retrieved data " + test_format[1] + " the '" +
topic + "' uORB topic\033[0m")
print(
"\033[34m--------------------------------------------------------------" + "\033[0m\n")
exit(0)

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/test/test_input.py

View File

@@ -0,0 +1,84 @@
#!/usr/bin/env python3
################################################################################
#
# Copyright 2019 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.
#
################################################################################
# This script tests the input data on a specific topic using the "listener"
# app in PX4. If no output comes or there's a "never published" output
# out of the app, the test fails.
import argparse
import os
from sys import exit
from subprocess import call, check_output, DEVNULL
from time import sleep
if __name__ == "__main__":
parser = argparse.ArgumentParser()
parser.add_argument("-b", "--px4-binary-dir", dest='px4_binary', type=str,
help="Directory where the PX4 SITL daemon binaries are stored", required=True)
parser.add_argument("-n", "--node-name", dest='node_name', type=str,
help="Name of the node publishing the to the topic", required=True)
parser.add_argument("-p", "--package-name", dest='package_name', type=str,
help="ROS 2 package name of the node", required=True)
parser.add_argument("-t", "--topic-name", dest='topic_name', type=str,
help="Topic name to test the output to the autopilot", required=True)
# Parse arguments
args = parser.parse_args()
test_cmd = "/bin/bash -c '" + \
os.path.join(args.px4_binary,
"px4-listener") + " " + args.topic_name + "'"
print("\n\033[93m-- " + args.topic_name +
" uORB data test launched:\033[0m")
# start the ROS 2 node
call("ros2 run " + args.package_name + " " + args.node_name + " &", shell=True)
sleep(3)
# call the 'listener' command for the '<topic_name>' uORB topic
output = check_output(test_cmd, shell=True, universal_newlines=True)
call("killall " + args.node_name,
shell=True, stdout=DEVNULL, stderr=DEVNULL)
if output and "never published" not in output:
print(
"\n\033[42m-- Successfully obtained data on '" + args.topic_name + "' uORB topic. microRTPS bridge is up! Output:\033[0m")
print("\033[97m" + output + "\033[0m")
exit(0)
else:
print(
"\n\033[41m-- Something went wrong. Please check if the microRTPS bridge is functioning correctly.\033[0m\n")
exit(1)

View File

@@ -1 +0,0 @@
/home/ubuntu/ros2_ws/src/px4_ros_com/test/test_output.py

View File

@@ -0,0 +1,71 @@
#!/usr/bin/env python3
################################################################################
#
# Copyright 2019 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.
#
################################################################################
# This script tests the output of 'ros2 topic echo /<TopicName>'
# to evaluate if there's data output coming out of it. If the log output file
# is empty, means that there's no output on the topic, so the test fails
import argparse
from os import remove
from sys import exit
from subprocess import call, TimeoutExpired
if __name__ == "__main__":
parser = argparse.ArgumentParser()
parser.add_argument("-t", "--topic-name", dest='topic_name', type=str,
help="Topic name to test the output to the autopilot", required=True)
# Parse arguments
args = parser.parse_args()
timeout = 3 # seconds
try:
print(
"\n\033[93m" + "-- " + args.topic_name + "_PubSubTopic output test launched:\033[0m")
call("ros2 topic echo /" + args.topic_name + "_PubSubTopic", timeout=timeout, stdout=open(
"ros2_topic_echo_out", "w"), shell=True)
except TimeoutExpired as e:
output = open("ros2_topic_echo_out", "r").read()
if output:
print(
"\n\033[42m" + "-- Successfully obtained data on " + args.topic_name + "_PubSubTopic topic. microRTPS bridge is up! Output:\033[0m\n\n")
print("\033[97m" + output + "\033[0m")
remove("ros2_topic_echo_out")
exit(0)
else:
print(
"\n\033[41m" + "-- Something went wrong. Please check if the microRTPS bridge is functioning correctly.\033[0m\n")
remove("ros2_topic_echo_out")
exit(1)