mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Publish robot_state
This commit is contained in:
@@ -38,6 +38,7 @@
|
||||
#include "ur_msgs/Digital.h"
|
||||
#include "ur_msgs/Analog.h"
|
||||
#include "std_msgs/String.h"
|
||||
#include "std_msgs/Int32.h"
|
||||
#include <controller_manager/controller_manager.h>
|
||||
|
||||
class RosWrapper {
|
||||
@@ -423,6 +424,8 @@ private:
|
||||
"joint_states", 1);
|
||||
ros::Publisher wrench_pub = nh_.advertise<geometry_msgs::WrenchStamped>(
|
||||
"wrench", 1);
|
||||
ros::Publisher robot_state_pub = nh_.advertise<std_msgs::Int32>(
|
||||
"ur_driver/robot_state", 1);
|
||||
while (ros::ok()) {
|
||||
sensor_msgs::JointState joint_msg;
|
||||
joint_msg.name = robot_.getJointNames();
|
||||
@@ -453,6 +456,11 @@ private:
|
||||
wrench_msg.wrench.torque.z = tcp_force[5];
|
||||
wrench_pub.publish(wrench_msg);
|
||||
|
||||
//Publish robot state
|
||||
std_msgs::Int32 robot_state_msg;
|
||||
robot_state_msg.data = (int) robot_.rt_interface_->robot_state_->getRobotMode();
|
||||
robot_state_pub.publish(robot_state_msg);
|
||||
|
||||
robot_.rt_interface_->robot_state_->setDataPublished();
|
||||
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user