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

Check URDF to distinguish fixed joints from floating joints. Floating… #32

Merged
merged 1 commit into from
Sep 24, 2015
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
2 changes: 1 addition & 1 deletion include/robot_state_publisher/joint_state_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class JointStateListener{
/** Constructor
* \param tree The kinematic model of a robot, represented by a KDL Tree
*/
JointStateListener(const KDL::Tree& tree, const MimicMap& m);
JointStateListener(const KDL::Tree& tree, const MimicMap& m, const urdf::Model& model = urdf::Model());

/// Destructor
~JointStateListener();
Expand Down
4 changes: 3 additions & 1 deletion include/robot_state_publisher/robot_state_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <boost/scoped_ptr.hpp>
#include <tf/tf.h>
#include <tf/transform_broadcaster.h>
#include <urdf/model.h>
#include <kdl/frames.hpp>
#include <kdl/segment.hpp>
#include <kdl/tree.hpp>
Expand All @@ -64,7 +65,7 @@ class RobotStatePublisher
/** Constructor
* \param tree The kinematic model of a robot, represented by a KDL Tree
*/
RobotStatePublisher(const KDL::Tree& tree);
RobotStatePublisher(const KDL::Tree& tree, const urdf::Model& model = urdf::Model());

/// Destructor
~RobotStatePublisher(){};
Expand All @@ -82,6 +83,7 @@ class RobotStatePublisher

std::map<std::string, SegmentPair> segments_, segments_fixed_;
tf::TransformBroadcaster tf_broadcaster_;
const urdf::Model& model_;
};


Expand Down
6 changes: 3 additions & 3 deletions src/joint_state_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,8 @@ using namespace ros;
using namespace KDL;
using namespace robot_state_publisher;

JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m)
: state_publisher_(tree), mimic_(m)
JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m, const urdf::Model& model)
: state_publisher_(tree, model), mimic_(m)
{
ros::NodeHandle n_tilde("~");
ros::NodeHandle n;
Expand Down Expand Up @@ -164,7 +164,7 @@ int main(int argc, char** argv)
}
}

JointStateListener state_publisher(tree, mimic);
JointStateListener state_publisher(tree, mimic, model);
ros::spin();

return 0;
Expand Down
12 changes: 9 additions & 3 deletions src/robot_state_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,8 @@ using namespace ros;

namespace robot_state_publisher{

RobotStatePublisher::RobotStatePublisher(const KDL::Tree& tree)
RobotStatePublisher::RobotStatePublisher(const KDL::Tree& tree, const urdf::Model& model)
: model_(model)
{
// walk the tree and add segments to segments_
addChildren(tree.getRootSegment());
Expand All @@ -62,8 +63,13 @@ namespace robot_state_publisher{
const KDL::Segment& child = GetTreeElementSegment(children[i]->second);
SegmentPair s(GetTreeElementSegment(children[i]->second), root, child.getName());
if (child.getJoint().getType() == KDL::Joint::None){
segments_fixed_.insert(make_pair(child.getJoint().getName(), s));
ROS_DEBUG("Adding fixed segment from %s to %s", root.c_str(), child.getName().c_str());
if (model_.getJoint(child.getJoint().getName()) && model_.getJoint(child.getJoint().getName())->type == urdf::Joint::FLOATING){
ROS_INFO("Floating joint. Not adding segment from %s to %s. This TF can not be published based on joint_states info", root.c_str(), child.getName().c_str());
}
else{
segments_fixed_.insert(make_pair(child.getJoint().getName(), s));
ROS_DEBUG("Adding fixed segment from %s to %s", root.c_str(), child.getName().c_str());
}
}
else{
segments_.insert(make_pair(child.getJoint().getName(), s));
Expand Down