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

Add joint blacklist property #83

Merged
merged 1 commit into from
Nov 21, 2023
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: 2 additions & 0 deletions src/core/RobotModelConfig.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,8 @@ struct RobotModelConfig{
bool floating_base;
/** Optional: Link names that are possibly in contact with the environment. These have to be valid link names in the robot model.*/
ActiveContacts contact_points;

std::vector<std::string> joint_blacklist;
};

}
Expand Down
1 change: 1 addition & 0 deletions src/robot_models/hyrodyn/RobotModelHyrodyn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ bool RobotModelHyrodyn::configure(const RobotModelConfig& cfg){
return false;
}
base_frame = robot_urdf->getRoot()->name;
URDFTools::applyJointBlacklist(robot_urdf, cfg.joint_blacklist);

// Add floating base
has_floating_base = cfg.floating_base;
Expand Down
7 changes: 4 additions & 3 deletions src/robot_models/kdl/RobotModelKDL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ bool RobotModelKDL::configure(const RobotModelConfig& cfg){
LOG_ERROR("Unable to parse urdf model")
return false;
}
URDFTools::applyJointBlacklist(robot_urdf, cfg.joint_blacklist);
base_frame = robot_urdf->getRoot()->name;

// Joint names from URDF without floating base
Expand Down Expand Up @@ -313,7 +314,7 @@ const base::MatrixXd &RobotModelKDL::comJacobian(){
if(segmentName == full_tree.getRootSegment()->second.segment.getName())
continue;
std::string segmentNameCOG = segmentName + "_COG";

KDL::Vector segmentCOG = segment.getInertia().getCOG();
double segmentMass = segment.getInertia().getMass();

Expand All @@ -328,7 +329,7 @@ const base::MatrixXd &RobotModelKDL::comJacobian(){

COGSegmentNames.push_back(segmentNameCOG);
}

// compute com jacobian as (mass) weighted average over COG frame jacobians
for(const auto& segment_name : COGSegmentNames)
com_jac += (mass_map[segment_name] / totalMass) *
Expand Down Expand Up @@ -427,7 +428,7 @@ void RobotModelKDL::recursiveCOM(const KDL::SegmentMap::const_iterator& currentS
KDL::Segment segment = currentSegment->second.segment;
#endif
// If the segment has a real joint, get the joint position
if( segment.getJoint().getType() != KDL::Joint::None ) {
if( segment.getJoint().getType() != KDL::Joint::None ) {
const std::string name = segment.getJoint().getName();
if(joint_idx_map_kdl.count(name)==0){
LOG_ERROR_S << "recursiveCOM: KDL tree contains joint " << name << " but this joint does not exist in joint idx map" << std::endl;
Expand Down
3 changes: 2 additions & 1 deletion src/robot_models/pinocchio/RobotModelPinocchio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ bool RobotModelPinocchio::configure(const RobotModelConfig& cfg){
return false;
}
base_frame = robot_urdf->getRoot()->name;
URDFTools::applyJointBlacklist(robot_urdf, cfg.joint_blacklist);

try{
if(cfg.floating_base){
Expand Down Expand Up @@ -362,7 +363,7 @@ const base::MatrixXd &RobotModelPinocchio::jacobianDot(const std::string &root_f
throw std::runtime_error("Not implemented: jacobianDot has not been implemented for RobotModelPinocchio");
}

const base::MatrixXd &RobotModelPinocchio::jointSpaceInertiaMatrix(){
const base::MatrixXd &RobotModelPinocchio::jointSpaceInertiaMatrix(){

if(joint_state.time.isNull()){
LOG_ERROR("RobotModelPinocchio: You have to call update() with appropriately timestamped joint data at least once before requesting kinematic information!");
Expand Down
2 changes: 1 addition & 1 deletion src/robot_models/rbdl/RobotModelRBDL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ bool RobotModelRBDL::configure(const RobotModelConfig& cfg){
return false;
}
base_frame = robot_urdf->getRoot()->name;

URDFTools::applyJointBlacklist(robot_urdf, cfg.joint_blacklist);
joint_names = URDFTools::jointNamesFromURDF(robot_urdf);

// Temporary workaround: RBDL does not support rotations of the link invertias. Set them to zero.
Expand Down
Loading