-
Notifications
You must be signed in to change notification settings - Fork 249
readrobotstate
Once you have ROSSmartServo running and connected to a ROS Master, you are able to read the current state of the robot from ROS topics.
The following topics are available :
-
Position of the robot joints on
/iiwa/state/JointPosition
-
Torque values of the robot joints on
/iiwa/state/JointTorque
-
Stiffness values of the robot joints on
/iiwa/state/JointStiffness
available only if the robot is in JointImpedance Control Mode -
Damping values of the robot joints on
/iiwa/state/JointDamping
available only if the robot is in JointImpedance Control Mode -
Current velocities values of the robot joints on
/iiwa/state/JointVelocity
-
ROS's JointState of the robot on
/iiwa/state/joint_states
-
Cartesian Pose of robot (or tool) TCP on
/iiwa/state/CartesianPose
-
Cartesian Wrench of robot (or tool) TCP on
/iiwa/state/CartesianWrench
-
Signal that the robot reached its commanded destination on
/iiwa/state/DestinationReached
As for any topic in ROS, you can print out its stream from command line using rostopic echo, here is an example for the JointPosition topic :
rostopic echo /iiwa/state/JointPosition
. The same applies to any other of the aforementioned topics.
From code you can simply create a Subscriber within a ROS Node to the topic you want.
You can easily learn that from the ROS Tutorials.
Additionally, we provide an helper class in iiwa_ros - surprisingly called iiwaRos in a moment of wild imagination - that handles all the functionalities you might need.
For example, you could directly use iiwaRos in your own ROS package to read from any of the mentioned topics:
iiwa_msgs::JointPosition my_joint_position;
iiwa_ros::iiwaRos my_iiwa_ros_object;
[...]
my_iiwa_ros_object.init(); // this initializes all the subscribers, publishers and services, it has to be called after you are sure a ros::init() was called.
[...]
bool success = false;
if (my_iiwa_ros_object.getJointPosition(my_joint_position)) {
ROS_INFO_STREAM("I got a Joint Message and its contents is: " << my_joint_position.position.a1 << " " << my_joint_position.position.a2 << " " [...] );
}
else {
ROS_INFO_STREAM("No Joint Message available");
}
iiwaRos has a bunch of useful methods to use the ROS topics (to read and command the robot) and the ROS services (to change control mode, change velocity/acceleration and get the time left to destination). You can check out its methods.