Skip to content
Closed
Show file tree
Hide file tree
Changes from 3 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
2 changes: 1 addition & 1 deletion baxter_gazebo/launch/baxter_world.launch
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
to launching baxter_world -->
<arg name="load_robot_description" default="true"/>
<param if="$(arg load_robot_description)" name="robot_description"
command="$(find xacro)/xacro.py --inorder $(find baxter_description)/urdf/baxter.urdf.xacro gazebo:=true"/>
command="$(find xacro)/xacro $(find baxter_description)/urdf/baxter.urdf.xacro gazebo:=true"/>

<!-- We resume the logic in empty_world.launch, changing the name of the world to be launched -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
Expand Down
7 changes: 5 additions & 2 deletions baxter_sim_io/include/baxter_sim_io/qnode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,12 +34,15 @@
#ifndef baxter_sim_io_QNODE_HPP_
#define baxter_sim_io_QNODE_HPP_

#ifndef Q_MOC_RUN
#include <ros/ros.h>
#include <baxter_core_msgs/NavigatorState.h>
#include <baxter_core_msgs/DigitalIOState.h>
#endif

#include <string>
#include <QThread>
#include <QStringListModel>
#include <baxter_core_msgs/NavigatorState.h>
#include <baxter_core_msgs/DigitalIOState.h>

namespace baxter_sim_io {

Expand Down
8 changes: 8 additions & 0 deletions baxter_sim_kinematics/src/arm_kinematics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,9 @@
#include <cstring>
#include <ros/ros.h>
#include <baxter_sim_kinematics/arm_kinematics.h>
#if ROS_VERSION_MINIMUN(1, 14, 0) //Melodic
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm so sorry, but my original comment was typo.
ROS_VERSION_MINIMUN -> ROS_VERSION_MINIMUM
can you correct this?

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you!

#include <memory>
#endif

namespace arm_kinematics {

Expand Down Expand Up @@ -245,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
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm so sorry, but my original comment was typo.
ROS_VERSION_MINIMUN -> ROS_VERSION_MINIMUM
can you correct this?

std::shared_ptr<const urdf::Link> link = robot_model.getLink(tip_name);
std::shared_ptr<const urdf::Joint> joint;
#else
boost::shared_ptr<const urdf::Link> link = robot_model.getLink(tip_name);
boost::shared_ptr<const urdf::Joint> joint;
#endif
for (int i = 0; i < chain.getNrOfSegments(); i++)
while (link && link->name != root_name) {
if (!(link->parent_joint)) {
Expand Down