Skip to content

timetodestination

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

Are we there yet?

Using the KUKA APIs, ROSSmartServo provides a ROS Service to get updates on the time left for the robot to reach its last commanded destination.
Once you start ROSSmartServo the ROS Service will be advertized on /iiwa /state/timeToDestination .

The service request for this ROS Service is just empty. You just need to call the service and you will get a double.

The result could be :

  • a positive number how many seconds are left until the robot reaches its destination.
  • a negative number how many seconds are passed since the robot reached its last commanded destination.
  • -999 is something went wrong!

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.
[...]
double time = my_iiwa_ros_object.getTimeToDestinationService().getTimeToDestination();
if (time > 0) {
    ROS_INFO_STREAM(time << " seconds till the robot reaches its destination");
}
else  if (time == -999){
    ROS_INFO_STREAM("Something went wrong!");
}
else {
    ROS_INFO_STREAM(time << " seconds since the robot reached its destination");
}

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 [TimeToDestinationService class] (../blob/master/iiwa_ros/include/time_to_destination_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/state/timeToDestination ");
iiwa_msgs:: TimeToDestination config;

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 !");
}
Clone this wiki locally