50 std::string robot_desc_string;
52 if (!n.
getParam(
"robot_description", robot_desc_string))
54 ROS_FATAL(
"Couldn't get a robot_description from the param server");
64 if (!n.
getParam(
"katana_joints", joint_names))
81 ROS_ERROR(
"Array of joint names should contain all strings. (namespace: %s)",
89 motor_limits_[i].min_position = model.getJoint(joint_names_[i])->limits->lower;
90 motor_limits_[i].max_position = model.getJoint(joint_names_[i])->limits->upper;
99 if (!n.
getParam(
"katana_gripper_joints", gripper_joint_names))
116 ROS_ERROR(
"Array of gripper joint names should contain all strings. (namespace: %s)",
123 motor_limits_[NUM_JOINTS + i].joint_name = (std::string)name_value;
124 motor_limits_[NUM_JOINTS + i].min_position = model.getJoint(gripper_joint_names_[i])->limits->lower;
125 motor_limits_[NUM_JOINTS + i].max_position = model.getJoint(gripper_joint_names_[i])->limits->upper;
161 ROS_ERROR(
"Joint not found: %s.", joint_name.c_str());
virtual std::vector< std::string > getJointNames()
virtual int getJointIndex(std::string joint_name)
URDF_EXPORT bool initString(const std::string &xmlstring)
virtual double getMotorLimitMin(std::string joint_name)
std::vector< double > motor_angles_
std::vector< int > joint_types_
const size_t NUM_MOTORS
The number of motors in the katana (= all 5 "real" joints + the gripper)
std::vector< int > gripper_joint_types_
virtual std::vector< int > getGripperJointTypes()
std::vector< double > motor_velocities_
Type const & getType() const
std::vector< std::string > joint_names_
const size_t NUM_GRIPPER_JOINTS
The number of gripper_joints in the katana (= the two gripper finger joints)
std::vector< moveit_msgs::JointLimits > motor_limits_
virtual ~AbstractKatana()
virtual std::vector< std::string > getGripperJointNames()
virtual std::vector< double > getMotorVelocities()
virtual std::vector< double > getMotorAngles()
const std::string & getNamespace() const
virtual void freezeRobot()
std::vector< std::string > gripper_joint_names_
bool getParam(const std::string &key, std::string &s) const
virtual std::vector< int > getJointTypes()
virtual void refreshMotorStatus()
virtual double getMotorLimitMax(std::string joint_name)
const size_t NUM_JOINTS
The number of joints in the katana (= only the 5 "real" joints)
virtual std::vector< moveit_msgs::JointLimits > getMotorLimits()
const size_t GRIPPER_INDEX
The motor index of the gripper (used in all vectors – e.g., motor_angles_)