// Move j3 in order to give room for hand initialization
jp_type jp_init = wam.getJointPositions();
- jp_init[3] -= 0.35;
+ jp_init[3] -= 0.4;
usleep(500000);
wam.moveTo(jp_init);
hand_sprd_vel_srv = nh_.advertiseService("spread_vel", &WamNode::handSpreadVel, this); // bhand/spread_vel
//Set up the BarrettHand joint state publisher
- const char* bhand_jnts[] = {"inner_f1", "inner_f2", "inner_f3", "spread", "outer_f1", "outer_f2", "outer_f3"};
+ const char* bhand_jnts[] = {"bhand_finger1_joint_2", "bhand_finger2_joint_2", "bhand_finger3_joint_2", "bhand_spread", "bhand_finger1_joint_3", "bhand_finger2_joint_3", "bhand_finger3_joint_3"};
std::vector < std::string > bhand_joints(bhand_jnts, bhand_jnts + 7);
bhand_joint_state.name.resize(7);
bhand_joint_state.name = bhand_joints;
wam.gravityCompensate(true); // Turning on Gravity Compenstation by Default when starting the WAM Node
//Setting up WAM joint state publisher
- const char* wam_jnts[] = {"wam_j1", "wam_j2", "wam_j3", "wam_j4", "wam_j5", "wam_j6", "wam_j7"};
+ const char* wam_jnts[] = {"wam_joint_1", "wam_joint_2", "wam_joint_3", "wam_joint_4", "wam_joint_5", "wam_joint_6", "wam_joint_7"};
std::vector < std::string > wam_joints(wam_jnts, wam_jnts + 7);
wam_joint_state.name = wam_joints;
wam_joint_state.name.resize(DOF);