From e2f874ddb937077a7b92e4f5fe9cde3b64446cc0 Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Thu, 14 Feb 2019 17:48:32 +0100 Subject: [PATCH 1/4] Fix compilation on Ubuntu 18.04 w ROS Melodic --- baxter_sim_io/include/baxter_sim_io/qnode.hpp | 7 +++++-- baxter_sim_kinematics/src/arm_kinematics.cpp | 5 +++-- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/baxter_sim_io/include/baxter_sim_io/qnode.hpp b/baxter_sim_io/include/baxter_sim_io/qnode.hpp index 24696b6..f67f02a 100644 --- a/baxter_sim_io/include/baxter_sim_io/qnode.hpp +++ b/baxter_sim_io/include/baxter_sim_io/qnode.hpp @@ -34,12 +34,15 @@ #ifndef baxter_sim_io_QNODE_HPP_ #define baxter_sim_io_QNODE_HPP_ +#ifndef Q_MOC_RUN #include +#include +#include +#endif + #include #include #include -#include -#include namespace baxter_sim_io { diff --git a/baxter_sim_kinematics/src/arm_kinematics.cpp b/baxter_sim_kinematics/src/arm_kinematics.cpp index 24d7b0d..9c2f60d 100644 --- a/baxter_sim_kinematics/src/arm_kinematics.cpp +++ b/baxter_sim_kinematics/src/arm_kinematics.cpp @@ -34,6 +34,7 @@ #include #include #include +#include namespace arm_kinematics { @@ -245,8 +246,8 @@ bool Kinematics::loadModel(const std::string xml) { */ bool Kinematics::readJoints(urdf::Model &robot_model) { num_joints = 0; - boost::shared_ptr link = robot_model.getLink(tip_name); - boost::shared_ptr joint; + std::shared_ptr link = robot_model.getLink(tip_name); + std::shared_ptr joint; for (int i = 0; i < chain.getNrOfSegments(); i++) while (link && link->name != root_name) { if (!(link->parent_joint)) { From b390be08e0f6721cbb70d101e1fa9b2d931475e1 Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Sun, 10 Mar 2019 19:41:05 +0100 Subject: [PATCH 2/4] Fix xacro warning on melodic --- baxter_gazebo/launch/baxter_world.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/baxter_gazebo/launch/baxter_world.launch b/baxter_gazebo/launch/baxter_world.launch index ac43ae6..62c45c9 100644 --- a/baxter_gazebo/launch/baxter_world.launch +++ b/baxter_gazebo/launch/baxter_world.launch @@ -19,7 +19,7 @@ to launching baxter_world --> + command="$(find xacro)/xacro $(find baxter_description)/urdf/baxter.urdf.xacro gazebo:=true"/> From 933322704e7d87816212fc6af7c3ef11ee476ca7 Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Wed, 22 Apr 2020 12:55:55 +0200 Subject: [PATCH 3/4] Rollback conditional support for Kinetic --- baxter_sim_kinematics/src/arm_kinematics.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/baxter_sim_kinematics/src/arm_kinematics.cpp b/baxter_sim_kinematics/src/arm_kinematics.cpp index 9c2f60d..c401750 100644 --- a/baxter_sim_kinematics/src/arm_kinematics.cpp +++ b/baxter_sim_kinematics/src/arm_kinematics.cpp @@ -34,7 +34,9 @@ #include #include #include +#if ROS_VERSION_MINIMUN(1, 14, 0) //Melodic #include +#endif namespace arm_kinematics { @@ -246,8 +248,13 @@ bool Kinematics::loadModel(const std::string xml) { */ bool Kinematics::readJoints(urdf::Model &robot_model) { num_joints = 0; + #if ROS_VERSION_MINIMUN(1, 14, 0) // Melodic std::shared_ptr link = robot_model.getLink(tip_name); std::shared_ptr joint; + #else + boost::shared_ptr link = robot_model.getLink(tip_name); + boost::shared_ptr joint; + #endif for (int i = 0; i < chain.getNrOfSegments(); i++) while (link && link->name != root_name) { if (!(link->parent_joint)) { From de51c01d051074661b0bb79f722a0a7b80fb29fb Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Sat, 25 Apr 2020 19:08:06 +0200 Subject: [PATCH 4/4] Fix typo --- baxter_sim_kinematics/src/arm_kinematics.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/baxter_sim_kinematics/src/arm_kinematics.cpp b/baxter_sim_kinematics/src/arm_kinematics.cpp index c401750..92e85c0 100644 --- a/baxter_sim_kinematics/src/arm_kinematics.cpp +++ b/baxter_sim_kinematics/src/arm_kinematics.cpp @@ -34,7 +34,7 @@ #include #include #include -#if ROS_VERSION_MINIMUN(1, 14, 0) //Melodic +#if ROS_VERSION_MINIMUM(1, 14, 0) //Melodic #include #endif @@ -248,7 +248,7 @@ bool Kinematics::loadModel(const std::string xml) { */ bool Kinematics::readJoints(urdf::Model &robot_model) { num_joints = 0; - #if ROS_VERSION_MINIMUN(1, 14, 0) // Melodic + #if ROS_VERSION_MINIMUM(1, 14, 0) // Melodic std::shared_ptr link = robot_model.getLink(tip_name); std::shared_ptr joint; #else