Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Publish joint temperature #446

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
5 changes: 5 additions & 0 deletions ur_robot_driver/include/ur_robot_driver/hardware_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <ur_msgs/ToolDataMsg.h>
#include <ur_msgs/SetIO.h>
#include <ur_msgs/SetSpeedSliderFraction.h>
#include <sensor_msgs/Temperature.h>

#include <ur_controllers/speed_scaling_interface.h>
#include <ur_controllers/scaled_joint_command_interface.h>
Expand Down Expand Up @@ -177,6 +178,7 @@ class HardwareInterface : public hardware_interface::RobotHW
*/
void publishPose();

void publishJointTemperatures(const ros::Time& timestamp);
void publishIOData();
void publishToolData();
void publishRobotAndSafetyMode();
Expand Down Expand Up @@ -230,6 +232,7 @@ class HardwareInterface : public hardware_interface::RobotHW
urcl::vector6d_t joint_positions_;
urcl::vector6d_t joint_velocities_;
urcl::vector6d_t joint_efforts_;
urcl::vector6d_t joint_temperatures_;
urcl::vector6d_t fts_measurements_;
urcl::vector6d_t tcp_pose_;
std::bitset<18> actual_dig_out_bits_;
Expand All @@ -256,6 +259,8 @@ class HardwareInterface : public hardware_interface::RobotHW
std::bitset<11> safety_status_bits_;

std::unique_ptr<realtime_tools::RealtimePublisher<tf2_msgs::TFMessage>> tcp_pose_pub_;
typedef std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::Temperature>> JTPublisherPtr;
std::vector<JTPublisherPtr> joint_temperature_pubs_;
std::unique_ptr<realtime_tools::RealtimePublisher<ur_msgs::IOStates>> io_pub_;
std::unique_ptr<realtime_tools::RealtimePublisher<ur_msgs::ToolDataMsg>> tool_data_pub_;
std::unique_ptr<realtime_tools::RealtimePublisher<ur_dashboard_msgs::RobotMode>> robot_mode_pub_;
Expand Down
1 change: 1 addition & 0 deletions ur_robot_driver/resources/rtde_output_recipe.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
timestamp
actual_q
actual_qd
joint_temperatures
speed_scaling
target_speed_fraction
runtime_state
Expand Down
27 changes: 27 additions & 0 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ HardwareInterface::HardwareInterface()
, joint_positions_{ { 0, 0, 0, 0, 0, 0 } }
, joint_velocities_{ { 0, 0, 0, 0, 0, 0 } }
, joint_efforts_{ { 0, 0, 0, 0, 0, 0 } }
, joint_temperatures_{ { 0, 0, 0, 0, 0, 0 } }
, standard_analog_input_{ { 0, 0 } }
, standard_analog_output_{ { 0, 0 } }
, joint_names_(6)
Expand Down Expand Up @@ -354,6 +355,12 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
{
io_pub_->msg_.analog_out_states[i].pin = i;
}
for (size_t i = 0; i < joint_names_.size(); i++)
{
JTPublisherPtr joint_temperature_pub(new realtime_tools::RealtimePublisher<sensor_msgs::Temperature>(root_nh, "joint_temperatures/"+joint_names_[i], 1));
joint_temperature_pubs_.push_back(joint_temperature_pub);
}

tool_data_pub_.reset(new realtime_tools::RealtimePublisher<ur_msgs::ToolDataMsg>(robot_hw_nh, "tool_data", 1));

robot_mode_pub_.reset(
Expand Down Expand Up @@ -449,6 +456,7 @@ void HardwareInterface::read(const ros::Time& time, const ros::Duration& period)
readData(data_pkg, "runtime_state", runtime_state_);
readData(data_pkg, "actual_TCP_force", fts_measurements_);
readData(data_pkg, "actual_TCP_pose", tcp_pose_);
readData(data_pkg, "joint_temperatures", joint_temperatures_);
readData(data_pkg, "standard_analog_input0", standard_analog_input_[0]);
readData(data_pkg, "standard_analog_input1", standard_analog_input_[1]);
readData(data_pkg, "standard_analog_output0", standard_analog_output_[0]);
Expand Down Expand Up @@ -478,6 +486,7 @@ void HardwareInterface::read(const ros::Time& time, const ros::Duration& period)
extractToolPose(time);
transformForceTorque();
publishPose();
publishJointTemperatures(time);
publishRobotAndSafetyMode();

// pausing state follows runtime state when pausing
Expand Down Expand Up @@ -719,6 +728,24 @@ void HardwareInterface::publishPose()
}
}

void HardwareInterface::publishJointTemperatures(const ros::Time& timestamp)
{
for (size_t i = 0; i < joint_names_.size(); i++)
{
if (joint_temperature_pubs_[i])
{
if (joint_temperature_pubs_[i]->trylock())
{
joint_temperature_pubs_[i]->msg_.header.stamp = timestamp;
joint_temperature_pubs_[i]->msg_.header.frame_id = joint_names_[i];
joint_temperature_pubs_[i]->msg_.temperature = joint_temperatures_[i];

joint_temperature_pubs_[i]->unlockAndPublish();
}
}
}
}

void HardwareInterface::extractRobotStatus()
{
robot_status_resource_.mode =
Expand Down