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

Fix Windows conflicting macros and missing usleep #885

Merged
Merged
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: 3 additions & 0 deletions gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,9 @@ ament_target_dependencies(gazebo_ros_imu_sensor
"sensor_msgs"
"gazebo_dev"
)
target_link_libraries(gazebo_ros_imu_sensor
ImuSensorPlugin
)
ament_export_libraries(gazebo_ros_imu_sensor)

# gazebo_ros_ray_sensor
Expand Down
6 changes: 6 additions & 0 deletions gazebo_plugins/src/gazebo_ros_diff_drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,12 @@
#include <geometry_msgs/msg/twist.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sdf/sdf.hh>

#ifdef NO_ERROR
// NO_ERROR is a macro defined in Windows that's used as an enum in tf2
#undef NO_ERROR
#endif

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
Expand Down
6 changes: 6 additions & 0 deletions gazebo_plugins/src/gazebo_ros_p3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,12 @@
#include <gazebo_plugins/gazebo_ros_p3d.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>

#ifdef NO_ERROR
// NO_ERROR is a macro defined in Windows that's used as an enum in tf2
#undef NO_ERROR
#endif

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
Expand Down
32 changes: 16 additions & 16 deletions gazebo_ros/include/gazebo_ros/conversions/generic.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,31 +32,31 @@ static rclcpp::Logger conversions_logger = rclcpp::get_logger("gazebo_ros_conver
/// Generic conversion from an Ignition Math vector to another type.
/// \param[in] in Input vector.
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const ignition::math::Vector3d & in)
/// \tparam T Output type
template<class T>
T Convert(const ignition::math::Vector3d & in)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

/// Generic conversion from an Ignition Math quaternion to another type.
/// \param[in] in Input quaternion
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const ignition::math::Quaterniond & in)
/// \tparam T Output type
template<class T>
T Convert(const ignition::math::Quaterniond & in)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

/// Generic conversion from an Gazebo Time object to another type.
/// \param[in] in Input time;
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const gazebo::common::Time & in)
/// \tparam T Output type
template<class T>
T Convert(const gazebo::common::Time & in)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

/// \brief Specialized conversion from an Gazebo Time to a RCLCPP Time.
Expand All @@ -71,11 +71,11 @@ rclcpp::Time Convert(const gazebo::common::Time & in)
/// Generic conversion from an Gazebo Time message to another type.
/// \param[in] in Input time
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const gazebo::msgs::Time & in)
/// \tparam T Output type
template<class T>
T Convert(const gazebo::msgs::Time & in)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

} // namespace gazebo_ros
Expand Down
32 changes: 16 additions & 16 deletions gazebo_ros/include/gazebo_ros/conversions/geometry_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,11 @@ namespace gazebo_ros
/// Generic conversion from a ROS geometry vector message to another type.
/// \param[in] in Input message.
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const geometry_msgs::msg::Vector3 & in)
/// \tparam T Output type
template<class T>
T Convert(const geometry_msgs::msg::Vector3 & in)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

/// \brief Specialized conversion from a ROS vector message to an Ignition Math vector.
Expand All @@ -53,11 +53,11 @@ ignition::math::Vector3d Convert(const geometry_msgs::msg::Vector3 & msg)
/// Generic conversion from a ROS geometry point32 message to another type.
/// \param[in] in Input message.
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const geometry_msgs::msg::Point32 & in)
/// \tparam T Output type
template<class T>
T Convert(const geometry_msgs::msg::Point32 & in)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

/// \brief Specialized conversion from a ROS point32 message to an Ignition Math vector.
Expand All @@ -76,11 +76,11 @@ ignition::math::Vector3d Convert(const geometry_msgs::msg::Point32 & in)
/// Generic conversion from a ROS geometry point message to another type.
/// \param[in] in Input message.
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const geometry_msgs::msg::Point &)
/// \tparam T Output type
template<class T>
T Convert(const geometry_msgs::msg::Point &)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

/// TODO(louise) This may already exist somewhere else, since it's within the same lib
Expand Down Expand Up @@ -153,11 +153,11 @@ geometry_msgs::msg::Quaternion Convert(const ignition::math::Quaterniond & in)
/// Generic conversion from a ROS Quaternion message to another type
/// \param[in] in Input quaternion
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const geometry_msgs::msg::Quaternion & in)
/// \tparam T Output type
template<class T>
T Convert(const geometry_msgs::msg::Quaternion & in)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

/// \brief Specialized conversion from a ROS quaternion message to ignition quaternion
Expand Down
8 changes: 4 additions & 4 deletions gazebo_ros/include/gazebo_ros/conversions/sensor_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@ namespace gazebo_ros
/// \param[in] in Input message;
/// \param[in] min_intensity The minimum intensity value to clip the output intensities
/// \return Conversion result
/// \tparam OUT Output type
template<class OUT>
OUT Convert(const gazebo::msgs::LaserScanStamped & in, double min_intensity = 0.0)
/// \tparam T Output type
template<class T>
T Convert(const gazebo::msgs::LaserScanStamped & in, double min_intensity = 0.0)
{
OUT::ConversionNotImplemented;
T::ConversionNotImplemented;
}

/// \brief Specialized conversion from an Gazebo Laser Scan to a ROS Laser Scan.
Expand Down
8 changes: 8 additions & 0 deletions gazebo_ros/include/gazebo_ros/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,14 @@

#include <string>

#ifdef _WIN32

#include <chrono>
#include <thread>
#define usleep(usec) (std::this_thread::sleep_for(std::chrono::microseconds(usec)))

#endif // _WIN32

namespace gazebo_ros
{

Expand Down