mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 11:00:47 +02:00
Fixed compiler warnings
This commit is contained in:
@@ -32,9 +32,6 @@ private:
|
||||
std::set<std::string> joint_set_;
|
||||
double max_velocity_;
|
||||
|
||||
RobotState state_;
|
||||
std::array<double, 6> q_actual_, qd_actual_;
|
||||
|
||||
GoalHandle curr_gh_;
|
||||
std::atomic<bool> interrupt_traj_;
|
||||
std::atomic<bool> has_goal_, running_;
|
||||
@@ -44,6 +41,9 @@ private:
|
||||
|
||||
TrajectoryFollower& follower_;
|
||||
|
||||
RobotState state_;
|
||||
std::array<double, 6> q_actual_, qd_actual_;
|
||||
|
||||
void onGoal(GoalHandle gh);
|
||||
void onCancel(GoalHandle gh);
|
||||
|
||||
|
||||
@@ -55,7 +55,7 @@ private:
|
||||
void reset();
|
||||
|
||||
public:
|
||||
ROSController(URCommander& commander, std::vector<std::string>& joint_names, double max_vel_change);
|
||||
ROSController(URCommander& commander, TrajectoryFollower& follower, std::vector<std::string>& joint_names, double max_vel_change);
|
||||
virtual ~ROSController() { }
|
||||
// from RobotHW
|
||||
void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list, const std::list<hardware_interface::ControllerInfo>& stop_list);
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
#include <algorithm>
|
||||
#include "ur_modern_driver/ur/commander.h"
|
||||
#include "ur_modern_driver/ur/rt_state.h"
|
||||
#include "ur_modern_driver/ros/trajectory_follower.h"
|
||||
|
||||
class HardwareInterface
|
||||
{
|
||||
@@ -56,11 +57,11 @@ public:
|
||||
class PositionInterface : public HardwareInterface, public hardware_interface::PositionJointInterface
|
||||
{
|
||||
private:
|
||||
URCommander &commander_;
|
||||
TrajectoryFollower& follower_;
|
||||
std::array<double, 6> position_cmd_;
|
||||
|
||||
public:
|
||||
PositionInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface, std::vector<std::string> &joint_names);
|
||||
PositionInterface(TrajectoryFollower& follower, hardware_interface::JointStateInterface &js_interface, std::vector<std::string> &joint_names);
|
||||
virtual bool write();
|
||||
virtual void start();
|
||||
virtual void stop();
|
||||
|
||||
@@ -33,12 +33,12 @@ struct TrajectoryPoint
|
||||
class TrajectoryFollower
|
||||
{
|
||||
private:
|
||||
double servoj_time_, servoj_lookahead_time_, servoj_gain_;
|
||||
std::atomic<bool> running_;
|
||||
std::array<double, 6> last_positions_;
|
||||
URCommander &commander_;
|
||||
URServer server_;
|
||||
int reverse_port_;
|
||||
|
||||
double servoj_time_, servoj_lookahead_time_, servoj_gain_;
|
||||
std::string program_;
|
||||
|
||||
template <typename T>
|
||||
|
||||
Reference in New Issue
Block a user