Skip to content

configuresmartservo

Salvo Virga edited this page Jul 25, 2017 · 3 revisions

Setting a ControlMode at Runtime

Using the KUKA APIs, ROSSmartServo provides a ROS Service to change the Control Mode of the robot online.
Once you start ROSSmartServo the ROS Service will be advertised on /iiwa /configuration/configureSmartServo.

The following Control Modes are supported:

You just need to fill the service request with the right values and call the service. From the service definition, you have to select which control_mode to use. The service will only use the values of the selected control mode.

The control_mode is defined as an int, you can make use of the ControlMode.msg to select the right one.

In the same way, DesiredForceControlMode and SinePatternControlMode require you to select the coordinate of the tool frame along which the force has to be applied (X, Y, Z) as an int, you can make use of DOF.msg to do so.

WARNING: Playing in the realm of force manipulation might be dangerous, especially when in contact with humans. You need to take particular care of the settings you are going to use with this control modes. Remember that they will react as YOU command, and YOU are prone to error as any human being. A good idea is to not apply big changes in the control mode at once, but rather gradually, else you may cause sudden and rapid motions of the manipulator that will try to keep up with the commanded behavior. Once again, read the KUKA manuals.

C++ Examples

You can call the service like any other ROS Service, as explained in the ROS Tutorials.

Additionally, we provide a 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 easily call the aforementioned service:

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.
[...]
my_iiwa_ros_object.getSmartServoService().setDesiredForceMode(iiwa_msgs::DOF::Z, 2.0, 100); // The robot will apply 2N with 100N/m stiffness in the Z direction of the tool (or flange).

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.
The methods for just calling this service are actually provided by the [SmartServoService class] (../blob/master/iiwa_ros/include/smart_servo_service.h), you can just include that if you only need this service.


The same without any helper class would look like this:

ros::ServiceClient client = nh.serviceClient<iiwa_msgs::ConfigureSmartServo>("/iiwa/configuration/configureSmartServo");
iiwa_msgs::ConfigureSmartServo config;

config.control_mode = iiwa_msgs::ControlMode::DESIRED_FORCE; // This is equal to config.control_mode = 3.
config.desired_force. cartesian_dof = iiwa_msgs::DOF::Z; // This is equal to config.desired_force.cartesian_dof = 3.
config.desired_force.desired_force = 2.0; // 2 Newtons
config.desired_force. desired_stiffness = 100; // stiffness to 100 N/m

if (client.call(config)) {
    if(!config.response.success)
        ROS_ERROR_STREAM("Config failed, Java error: " << config.response.error);
    else
        ROS_INFO_STREAM("SmartServo Service successfully called.");
}
else {
    ROS_ERROR_STREAM("Config failed - service could not be called - QUITTING NOW !");
}

Something very similar would be for the other Control Modes, just check their definition in iiwa_msgs.

Clone this wiki locally