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"/> 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..92e85c0 100644 --- a/baxter_sim_kinematics/src/arm_kinematics.cpp +++ b/baxter_sim_kinematics/src/arm_kinematics.cpp @@ -34,6 +34,9 @@ #include #include #include +#if ROS_VERSION_MINIMUM(1, 14, 0) //Melodic +#include +#endif namespace arm_kinematics { @@ -245,8 +248,13 @@ bool Kinematics::loadModel(const std::string xml) { */ bool Kinematics::readJoints(urdf::Model &robot_model) { num_joints = 0; + #if ROS_VERSION_MINIMUM(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)) {