1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 18:10:47 +02:00

corrected naming scheme of fts-transformation

This commit is contained in:
Felix Mauch
2019-06-12 11:56:24 +02:00
parent 25e9aafc14
commit adacb219c7
2 changed files with 3 additions and 3 deletions

View File

@@ -73,7 +73,7 @@ protected:
/*! /*!
* \brief Transforms force-torque measurements reported from the robot from base to tool frame * \brief Transforms force-torque measurements reported from the robot from base to tool frame
*/ */
void transform_force_torque(); void transformForceTorque();
std::unique_ptr<UrDriver> ur_driver_; std::unique_ptr<UrDriver> ur_driver_;

View File

@@ -226,7 +226,7 @@ void HardwareInterface ::read(const ros::Time& time, const ros::Duration& period
} }
// Transform fts measurements to tool frame // Transform fts measurements to tool frame
transform_force_torque(); transformForceTorque();
// pausing state follows runtime state when pausing // pausing state follows runtime state when pausing
if (runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PAUSED)) if (runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PAUSED))
@@ -312,7 +312,7 @@ uint32_t HardwareInterface ::getControlFrequency() const
throw std::runtime_error("ur_driver is not yet initialized"); throw std::runtime_error("ur_driver is not yet initialized");
} }
void HardwareInterface ::transform_force_torque() void HardwareInterface ::transformForceTorque()
{ {
double tcp_angle = std::sqrt(std::pow(tcp_pose_[3], 2) + std::pow(tcp_pose_[4], 2) + std::pow(tcp_pose_[5], 2)); double tcp_angle = std::sqrt(std::pow(tcp_pose_[3], 2) + std::pow(tcp_pose_[4], 2) + std::pow(tcp_pose_[5], 2));