Skip to content
This repository has been archived by the owner on Jan 16, 2019. It is now read-only.

Publish industrial_msgs::RobotStatus #5

Merged
merged 4 commits into from
Jan 2, 2018
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ find_package(catkin REQUIRED COMPONENTS
actionlib
control_msgs
geometry_msgs
industrial_msgs
roscpp
sensor_msgs
std_srvs
Expand Down
7 changes: 6 additions & 1 deletion include/ur_modern_driver/ros/mb_publisher.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#pragma once

#include <industrial_msgs/RobotStatus.h>
#include <ros/ros.h>
#include <ur_msgs/Analog.h>
#include <ur_msgs/Digital.h>
Expand All @@ -14,6 +15,7 @@ class MBPublisher : public URStatePacketConsumer
private:
NodeHandle nh_;
Publisher io_pub_;
Publisher status_pub_;

template <size_t N>
inline void appendDigital(std::vector<ur_msgs::Digital>& vec, std::bitset<N> bits)
Expand All @@ -28,9 +30,12 @@ class MBPublisher : public URStatePacketConsumer
}

void publish(ur_msgs::IOStates& io_msg, SharedMasterBoardData& data);
void publishRobotStatus(const RobotModeData_V1_X& data) const;
void publishRobotStatus(const RobotModeData_V3_0__1& data) const;

public:
MBPublisher() : io_pub_(nh_.advertise<ur_msgs::IOStates>("ur_driver/io_states", 1))
, status_pub_(nh_.advertise<industrial_msgs::RobotStatus>("robot_status", 1))
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should this perhaps be published at "ur_driver/robot_status"?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We could, but that would make it non-compliant with other ros-i robot drivers.

A remap can fix that though.

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Alright yes that makes perfect sense, let's keep it as it is here then.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Well .. let's actually not.

All topics for the ur_driver are below a ur_driver namespace already, so having this one outside it breaks that.

If/when we need to make this driver ros-i compliant, we can either blanketly remap everything or update the topics.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So I'll add the prefix for consistencies sake?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe that makes the most sense for now, yes.

Otherwise users would find all topics of the driver under the ur_driver namespace, but a lone (and seemingly unrelated) /robot_status topic in the global one.

{
}

Expand All @@ -51,4 +56,4 @@ class MBPublisher : public URStatePacketConsumer
virtual void stopConsumer()
{
}
};
};
2 changes: 1 addition & 1 deletion include/ur_modern_driver/ros/rt_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,4 +71,4 @@ class RTPublisher : public URRTPacketConsumer
virtual void stopConsumer()
{
}
};
};
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
<build_depend>actionlib</build_depend>
<build_depend>control_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>industrial_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>trajectory_msgs</build_depend>
Expand All @@ -57,6 +58,7 @@
<run_depend>actionlib</run_depend>
<run_depend>control_msgs</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>industrial_msgs</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>trajectory_msgs</run_depend>
Expand Down
78 changes: 77 additions & 1 deletion src/ros/mb_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,79 @@ void MBPublisher::publish(ur_msgs::IOStates& io_msg, SharedMasterBoardData& data
io_pub_.publish(io_msg);
}

void MBPublisher::publishRobotStatus(const RobotModeData_V1_X& data) const
{
industrial_msgs::RobotStatus msg;

//note that this is true as soon as the drives are powered,
//even if the breakes are still closed
//which is in slight contrast to the comments in the
//message definition
msg.drives_powered.val = data.robot_power_on;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can robot_power_on ever be true if real_robot_enabled is false? Perhaps in ur-sim?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

testing with ursim I get the following output in Poly:
0000d05h41m35.184s RobotInterface C102A0: Real Robot not connected - Simulating Robot

meanwhile the robot mode contains the following data:

when I turn off the robot:
robot_power_on: 0 physical robot: 0 real_robot: 1 mode: 3 (POWER_OFF)

when I turn on the robot but do not yet release the brakes (ON but not START):
robot_power_on: 1 physical robot: 0 real_robot: 1 mode: 5 (IDLE)

when I release the brakes:
robot_power_on: 1 physical robot: 0 real_robot: 1 mode: 7 (RUNNING)

so I'm not sure what real_robot_enabled is supposed to tell us, maybe there is a way to switch to moving a simulated robot on the actual controller?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

so I'm not sure what real_robot_enabled is supposed to tell us, maybe there is a way to switch to moving a simulated robot on the actual controller?

There is a two-option selection bullet list at the bottom right or left (don't remember) that contains those two options. I've never used it, but IIRC you can use it to switch to a virtual robot.

Copy link
Collaborator

@gavanderhoorn gavanderhoorn Nov 15, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The difference between IDLE and RUNNING may indicate that RUNNING would be better indicator of drives_powered?

Edit: hm, no. That makes no sense.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ok, found that (for the reference: it is in 'Program Robot' -> 'Move' or 'I/O' but I can only change it to simulated in IO), real_robot_enabled then does turn to false. But this doesn't map to any of the industrial_msgs::RobotStatus fields does it?

Copy link
Author

@simonschmeisser simonschmeisser Nov 15, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

# Drive power status: True if drives are powered.  Motion commands will 
# automatically enable the drives if required.  Drive power is not requred
# for possible motion
industrial_msgs/TriState drives_powered

So yes, maybe drives powered should be obtained from Mode == RUNNING as in that halfway on mode (breakes still on) it does not automatically start moving. But then drives_powered would be the same as motion_possible. And as far as I understand motion_possible is authorative?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think drives_powered should reflect the status of the drives (ie: robot_power_on.

RUNNING could then be used in the predicate for motion_possible (ie: mode != RUNNING -> motion_possible = false.


msg.e_stopped.val = data.emergency_stopped;

//I found no way to reliably get information if the robot is moving
//data.programm_running would be true when using this driver to move the robot
//but it would also be true when another programm is running that might not
//in fact contain any movement commands
msg.in_motion.val = industrial_msgs::TriState::UNKNOWN;

//the error code, if any, is not transmitted by this protocol
//it can and should be fetched seperately
msg.error_code = 0;

//note that e-stop is handled by a seperate variable
msg.in_error.val = data.protective_stopped;

if (data.robot_mode == robot_mode_V1_X::ROBOT_FREEDRIVE_MODE)
msg.mode.val = industrial_msgs::RobotMode::MANUAL;
else
msg.mode.val = industrial_msgs::RobotMode::AUTO;

//todo: verify that this correct, there is also ROBOT_READY_MODE
msg.motion_possible.val = (data.robot_mode == robot_mode_V1_X::ROBOT_RUNNING_MODE)
? industrial_msgs::TriState::ON : industrial_msgs::TriState::OFF;

status_pub_.publish(msg);
}

void MBPublisher::publishRobotStatus(const RobotModeData_V3_0__1& data) const
{
industrial_msgs::RobotStatus msg;

//note that this is true as soon as the drives are powered,
//even if the breakes are still closed
//which is in slight contrast to the comments in the
//message definition
msg.drives_powered.val = data.robot_power_on;

msg.e_stopped.val = data.emergency_stopped;

//the error code, if any, is not transmitted by this protocol
//it can and should be fetched seperately
msg.error_code = 0;

//I found no way to reliably get information if the robot is moving
//data.programm_running would be true when using this driver to move the robot
//but it would also be true when another programm is running that might not
//in fact contain any movement commands
msg.in_motion.val = industrial_msgs::TriState::UNKNOWN;

//note that e-stop is handled by a seperate variable
msg.in_error.val = data.protective_stopped;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is protective_stopped high for all errors that can occur?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

there does not seem to be another way to be informed about errors looking at the format in robot_mode.h

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What about emergency_stopped? That would definitely be an 'in_error' situation, but that's not captured here at the moment. ros-industrial-attic#143 makes in_error the union of protective_stopped and emergency_stopped.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ah okay, I thought of e-stopped more like a state and the error would appear separately once you try moving despite it being in e-stopped mode. But I can change it to said union. This would again ask for a place to define the "vendor specific" error codes and then setting error_code to differentiate protective_stopped

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

"Vendor specific" means that the error codes are defined by the vendor. Not by us, for every vendor.

This field is typically populated by copying the error code that the robot controller gives you for different errors. On Fanucs fi you would be copying the code returned by the ERR_DATA(..) Karel function (which is typically a 5 or 6 digit number).

Those codes are defined by Fanuc. We don't make them up ourselves.

UR has similar codes I believe (just take a look at the log on the TP), but I'm not sure we can retrieve those from somewhere.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I thought of e-stopped more like a state and the error would appear separately once you try moving despite it being in e-stopped mode.

That could definitely be a way to implement it, but we would need a way to reliably determine which of the two it is. I don't have a scripting manual with me right now, but if there is a get_last_error_code() function that we can use, then we can definitely do what you propose.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You're correct. e_stopped is the state, and in_error should follow from whether the robot controller defines this as an error.

Let's keep what you have for now.

Sorry for the noise.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

re: vendor specific codes: looking at a UR we have here I keep seeing C100A5 in the log whenever the robot is Robot changed mode: EMERGENCY STOPPED.

Those are the codes that would go into error_code.


msg.motion_possible.val = (data.robot_mode == robot_mode_V3_X::RUNNING)
? industrial_msgs::TriState::ON : industrial_msgs::TriState::OFF;

if (data.control_mode == robot_control_mode_V3_X::TEACH)
msg.mode.val = industrial_msgs::RobotMode::MANUAL;
else
msg.mode.val = industrial_msgs::RobotMode::AUTO;

status_pub_.publish(msg);
}

bool MBPublisher::consume(MasterBoardData_V1_X& data)
{
ur_msgs::IOStates io_msg;
Expand All @@ -42,13 +115,16 @@ bool MBPublisher::consume(MasterBoardData_V3_2& data)

bool MBPublisher::consume(RobotModeData_V1_X& data)
{
publishRobotStatus(data);
return true;
}
bool MBPublisher::consume(RobotModeData_V3_0__1& data)
{
publishRobotStatus(data);
return true;
}
bool MBPublisher::consume(RobotModeData_V3_2& data)
{
publishRobotStatus(data);
return true;
}
}
2 changes: 1 addition & 1 deletion src/ros/rt_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,4 +116,4 @@ bool RTPublisher::consume(RTState_V3_0__1& state)
bool RTPublisher::consume(RTState_V3_2__3& state)
{
return publish(state);
}
}