diff --git a/pal-hardware-gazebo/patches/patch-aa b/pal-hardware-gazebo/patches/patch-aa new file mode 100644 index 0000000000000000000000000000000000000000..4a7663281a6123fabdea2f9b42fbe9ab237902f2 --- /dev/null +++ b/pal-hardware-gazebo/patches/patch-aa @@ -0,0 +1,14 @@ +--- src/pal_hardware_gazebo.cpp ++++ src/pal_hardware_gazebo.cpp +@@ -287,7 +287,7 @@ bool PalHardwareGazebo::parseIMUSensors(ros::NodeHandle& nh, gazebo::physics::Mo + ImuSensorDefinitionPtr imu(new ImuSensorDefinition(sensor_name, sensor_frame_id)); + imu->gazebo_imu_sensor = imu_sensor; + imuSensorDefinitions_.push_back(imu); +- imu_sensor->SetWorldToReferencePose(); ++ imu_sensor->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity); + ROS_INFO_STREAM("Parsed imu sensor: " << sensor_name << " in frame: " << sensor_frame_id); + } + return true; +-- +2.7.4 + diff --git a/pal-hardware-gazebo/patches/patch-ab b/pal-hardware-gazebo/patches/patch-ab new file mode 100644 index 0000000000000000000000000000000000000000..738b3012a3c5aaa09040f1c99760d6a8aa5e49ea --- /dev/null +++ b/pal-hardware-gazebo/patches/patch-ab @@ -0,0 +1,47 @@ +--- src/pal_hardware_gazebo.cpp ++++ src/pal_hardware_gazebo.cpp +@@ -42,6 +42,7 @@ + #include <pal_hardware_gazebo/pal_hardware_gazebo.h> + + #include <dynamic_introspection/dynamic_introspection.h> ++#include <gazebo/gazebo_config.h> + + typedef Eigen::Vector3d eVector3; + typedef Eigen::Isometry3d eMatrixHom; +@@ -194,8 +195,8 @@ bool PalHardwareGazebo::parseForceTorqueSensors(ros::NodeHandle& nh, + + if (!urdf_sensor_joint) + { +- ROS_ERROR_STREAM("Problem finding joint: " +- << ft->sensorJointName << " to attach FT sensor in robot model"); ++ ROS_ERROR_STREAM("Problem finding joint: " << ft->sensorJointName ++ << " to attach FT sensor in robot model"); + return false; + } + +@@ -243,8 +244,7 @@ bool PalHardwareGazebo::parseForceTorqueSensors(ros::NodeHandle& nh, + if (!ft->gazebo_joint) + { + ROS_ERROR_STREAM("Could not find joint '" +- << ft->sensorJointName +- << "' to which a force-torque sensor is attached."); ++ << ft->sensorJointName << "' to which a force-torque sensor is attached."); + return false; + } + +@@ -287,7 +287,12 @@ bool PalHardwareGazebo::parseIMUSensors(ros::NodeHandle& nh, gazebo::physics::Mo + ImuSensorDefinitionPtr imu(new ImuSensorDefinition(sensor_name, sensor_frame_id)); + imu->gazebo_imu_sensor = imu_sensor; + imuSensorDefinitions_.push_back(imu); ++ ++#if GAZEBO_MAJOR_VERSION >= 8 ++#if GAZEBO_MINOR_VERSION >= 11 + imu_sensor->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity); ++#endif ++#endif + ROS_INFO_STREAM("Parsed imu sensor: " << sensor_name << " in frame: " << sensor_frame_id); + } + return true; +-- +2.7.4 + diff --git a/pal-hardware-gazebo/patches/patch-ac b/pal-hardware-gazebo/patches/patch-ac new file mode 100644 index 0000000000000000000000000000000000000000..c0e56f47fb45c11914d061b3eabac691b1cea1c8 --- /dev/null +++ b/pal-hardware-gazebo/patches/patch-ac @@ -0,0 +1,18 @@ +--- src/pal_hardware_gazebo.cpp ++++ src/pal_hardware_gazebo.cpp +@@ -288,11 +288,9 @@ bool PalHardwareGazebo::parseIMUSensors(ros::NodeHandle& nh, gazebo::physics::Mo + imu->gazebo_imu_sensor = imu_sensor; + imuSensorDefinitions_.push_back(imu); + +-#if GAZEBO_MAJOR_VERSION >= 8 +-#if GAZEBO_MINOR_VERSION >= 11 ++#if GAZEBO_MAJOR_VERSION >= 8 || (GAZEBO_MAJOR_VERSION == 7 && GAZEBO_MAJOR_VERSION >= 11) + imu_sensor->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity); + #endif +-#endif + ROS_INFO_STREAM("Parsed imu sensor: " << sensor_name << " in frame: " << sensor_frame_id); + } + return true; +-- +2.7.4 + diff --git a/pal-hardware-gazebo/patches/patch-ad b/pal-hardware-gazebo/patches/patch-ad new file mode 100644 index 0000000000000000000000000000000000000000..765aa979a06116da52525fe0291f93baf1b395e6 --- /dev/null +++ b/pal-hardware-gazebo/patches/patch-ad @@ -0,0 +1,14 @@ +--- src/pal_hardware_gazebo.cpp ++++ src/pal_hardware_gazebo.cpp +@@ -288,7 +288,7 @@ bool PalHardwareGazebo::parseIMUSensors(ros::NodeHandle& nh, gazebo::physics::Mo + imu->gazebo_imu_sensor = imu_sensor; + imuSensorDefinitions_.push_back(imu); + +-#if GAZEBO_MAJOR_VERSION >= 8 || (GAZEBO_MAJOR_VERSION == 7 && GAZEBO_MAJOR_VERSION >= 11) ++#if GAZEBO_MAJOR_VERSION >= 8 || (GAZEBO_MAJOR_VERSION == 7 && GAZEBO_MINOR_VERSION >= 11) + imu_sensor->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity); + #endif + ROS_INFO_STREAM("Parsed imu sensor: " << sensor_name << " in frame: " << sensor_frame_id); +-- +2.7.4 +