mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
get frequency from robot
This commit is contained in:
@@ -15,7 +15,6 @@
|
||||
#ifndef UR_CONTROLLERS_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED
|
||||
#define UR_CONTROLLERS_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED
|
||||
|
||||
|
||||
#include <joint_trajectory_controller/hardware_interface_adapter.h>
|
||||
#include "ur_controllers/scaled_joint_command_interface.h"
|
||||
|
||||
@@ -43,20 +42,24 @@ template <class State>
|
||||
class HardwareInterfaceAdapter<ur_controllers::ScaledPositionJointInterface, State>
|
||||
{
|
||||
public:
|
||||
HardwareInterfaceAdapter() : joint_handles_ptr_(0) {}
|
||||
HardwareInterfaceAdapter() : joint_handles_ptr_(0)
|
||||
{
|
||||
}
|
||||
|
||||
bool init(std::vector<ur_controllers::ScaledJointHandle>& joint_handles, ros::NodeHandle& /*controller_nh*/)
|
||||
{
|
||||
// Store pointer to joint handles
|
||||
joint_handles_ptr_ = &joint_handles;
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void starting(const ros::Time& /*time*/)
|
||||
{
|
||||
if (!joint_handles_ptr_) {return;}
|
||||
if (!joint_handles_ptr_)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
// Semantic zero for commands
|
||||
for (auto& jh : *joint_handles_ptr_)
|
||||
@@ -65,20 +68,23 @@ public:
|
||||
}
|
||||
}
|
||||
|
||||
void stopping(const ros::Time& /*time*/) {}
|
||||
void stopping(const ros::Time& /*time*/)
|
||||
{
|
||||
}
|
||||
|
||||
void updateCommand(const ros::Time& /*time*/,
|
||||
const ros::Duration& /*period*/,
|
||||
const State& desired_state,
|
||||
const State& /*state_error*/)
|
||||
void updateCommand(const ros::Time& /*time*/, const ros::Duration& /*period*/, const State& desired_state,
|
||||
const State& /*state_error*/)
|
||||
{
|
||||
// Forward desired position to command
|
||||
const unsigned int n_joints = joint_handles_ptr_->size();
|
||||
for (unsigned int i = 0; i < n_joints; ++i) {(*joint_handles_ptr_)[i].setCommand(desired_state.position[i]);}
|
||||
for (unsigned int i = 0; i < n_joints; ++i)
|
||||
{
|
||||
(*joint_handles_ptr_)[i].setCommand(desired_state.position[i]);
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
std::vector<ur_controllers::ScaledJointHandle>* joint_handles_ptr_;
|
||||
};
|
||||
|
||||
#endif // ifndef UR_CONTROLLERS_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED
|
||||
#endif // ifndef UR_CONTROLLERS_HARDWARE_INTERFACE_ADAPTER_H_INCLUDED
|
||||
|
||||
@@ -36,7 +36,7 @@ public:
|
||||
|
||||
private:
|
||||
std::vector<SpeedScalingHandle> sensors_;
|
||||
//TODO: We should use a better datatype later on
|
||||
// TODO: We should use a better datatype later on
|
||||
typedef std::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Float64> > RtPublisherPtr;
|
||||
std::vector<RtPublisherPtr> realtime_pubs_;
|
||||
std::vector<ros::Time> last_publish_times_;
|
||||
|
||||
@@ -18,7 +18,6 @@
|
||||
#include <pluginlib/class_list_macros.hpp>
|
||||
#include <trajectory_interface/quintic_spline_segment.h>
|
||||
|
||||
|
||||
namespace position_controllers
|
||||
{
|
||||
typedef ur_controllers::ScaledJointTrajectoryController<trajectory_interface::QuinticSplineSegment<double>,
|
||||
|
||||
@@ -86,4 +86,3 @@ void SpeedScalingStateController ::stopping(const ros::Time& /*time*/)
|
||||
} // namespace ur_controllers
|
||||
|
||||
PLUGINLIB_EXPORT_CLASS(ur_controllers::SpeedScalingStateController, controller_interface::ControllerBase)
|
||||
|
||||
|
||||
Reference in New Issue
Block a user