four_wheel_steering.h
Go to the documentation of this file.
1 // NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials
2 
3 #pragma once
4 
5 
6 // ROS
7 #include <ros/ros.h>
8 #include <std_msgs/Float64.h>
9 #include <std_srvs/Empty.h>
10 
11 // ros_control
12 #include <controller_manager/controller_manager.h>
17 
18 // NaN
19 #include <limits>
20 
21 // ostringstream
22 #include <sstream>
23 
25 {
26 public:
28  : running_(true)
31  {
32  std::vector<std::string> velocity_joints_name = {"front_left_wheel", "front_right_wheel",
33  "rear_left_wheel", "rear_right_wheel"};
34  // Connect and register the joint state and velocity interface
35  for (unsigned int i = 0; i < velocity_joints_name.size(); ++i)
36  {
37 
38  hardware_interface::JointStateHandle state_handle(velocity_joints_name[i], &joints_[i].position, &joints_[i].velocity, &joints_[i].effort);
40 
41  hardware_interface::JointHandle vel_handle(state_handle, &joints_[i].velocity_command);
43  }
44 
45  std::vector<std::string> position_joints_name = {"front_left_steering_joint", "front_right_steering_joint",
46  "rear_left_steering_joint", "rear_right_steering_joint"};
47  // Connect and register the joint state and position interface
48  for (unsigned int i = 0; i < position_joints_name.size(); ++i)
49  {
50  hardware_interface::JointStateHandle state_handle(position_joints_name[i], &steering_joints_[i].position, &steering_joints_[i].velocity, &steering_joints_[i].effort);
52 
53  hardware_interface::JointHandle pos_handle(state_handle, &steering_joints_[i].position_command);
55  }
56 
60  }
61 
62  ros::Time getTime() const {return ros::Time::now();}
63  ros::Duration getPeriod() const {return ros::Duration(0.01);}
64 
65  void read()
66  {
67  // Read the joint state of the robot into the hardware interface
68  if (running_)
69  {
70  for (unsigned int i = 0; i < 4; ++i)
71  {
72  // Note that joints_[i].position will be NaN for one more cycle after we start(),
73  // but that is consistent with the knowledge we have about the state
74  // of the robot.
75  joints_[i].position += joints_[i].velocity*getPeriod().toSec(); // update position
76  joints_[i].velocity = joints_[i].velocity_command; // might add smoothing here later
77  }
78  for (unsigned int i = 0; i < 4; ++i)
79  {
80  steering_joints_[i].position = steering_joints_[i].position_command; // might add smoothing here later
81  }
82  }
83  else
84  {
85  for (unsigned int i = 0; i < 4; ++i)
86  {
87  joints_[i].position = std::numeric_limits<double>::quiet_NaN();
88  joints_[i].velocity = std::numeric_limits<double>::quiet_NaN();
89  }
90  for (unsigned int i = 0; i < 4; ++i)
91  {
92  steering_joints_[i].position = std::numeric_limits<double>::quiet_NaN();
93  steering_joints_[i].velocity = std::numeric_limits<double>::quiet_NaN();
94  }
95  }
96  }
97 
98  void write()
99  {
100  // Write the commands to the joints
101  std::ostringstream os;
102  for (unsigned int i = 0; i < 3; ++i)
103  {
104  os << joints_[i].velocity_command << ", ";
105  }
106  os << joints_[3].velocity_command;
107 
108  ROS_DEBUG_STREAM("Commands for joints: " << os.str());
109 
110  os.str("");
111  for (unsigned int i = 0; i < 3; ++i)
112  {
113  os << steering_joints_[i].position_command << ", ";
114  }
116  ROS_DEBUG_STREAM("Commands for steering joints: " << os.str());
117 
118  }
119 
120  bool start_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
121  {
122  running_ = true;
123  return true;
124  }
125 
126  bool stop_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
127  {
128  running_ = false;
129  return true;
130  }
131 
132 private:
136 
137  struct Joint
138  {
139  double position;
140  double velocity;
141  double effort;
143 
145  } joints_[4];
146 
148  {
149  double position;
150  double velocity;
151  double effort;
153 
155  } steering_joints_[4];
156  bool running_;
157 
161 };
FourWheelSteering::Joint::velocity_command
double velocity_command
Definition: four_wheel_steering.h:142
hardware_interface::JointStateInterface
ros.h
FourWheelSteering::joints_
struct FourWheelSteering::Joint joints_[4]
realtime_buffer.h
hardware_interface::InterfaceManager::registerInterface
void registerInterface(T *iface)
FourWheelSteering::stop_srv_
ros::ServiceServer stop_srv_
Definition: four_wheel_steering.h:160
FourWheelSteering::nh_
ros::NodeHandle nh_
Definition: four_wheel_steering.h:158
FourWheelSteering::SteeringJoint::SteeringJoint
SteeringJoint()
Definition: four_wheel_steering.h:154
FourWheelSteering::SteeringJoint::position_command
double position_command
Definition: four_wheel_steering.h:152
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
FourWheelSteering::start_callback
bool start_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: four_wheel_steering.h:120
FourWheelSteering::stop_callback
bool stop_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: four_wheel_steering.h:126
ros::ServiceServer
FourWheelSteering::Joint
Definition: four_wheel_steering.h:137
hardware_interface::VelocityJointInterface
FourWheelSteering::Joint::position
double position
Definition: four_wheel_steering.h:139
joint_command_interface.h
advertiseService
ServiceServer advertiseService(ros::NodeHandle n, std::string name, boost::function< bool(const typename ActionSpec::_action_goal_type::_goal_type &, typename ActionSpec::_action_result_type::_result_type &result)> service_cb)
hardware_interface::RobotHW
FourWheelSteering::running_
bool running_
Definition: four_wheel_steering.h:156
hardware_interface::JointStateHandle
FourWheelSteering::SteeringJoint
Definition: four_wheel_steering.h:147
FourWheelSteering
Definition: four_wheel_steering.h:24
FourWheelSteering::getPeriod
ros::Duration getPeriod() const
Definition: four_wheel_steering.h:63
ResourceManager< JointStateHandle >::registerHandle
void registerHandle(const JointStateHandle &handle)
FourWheelSteering::write
void write()
Definition: four_wheel_steering.h:98
joint_state_interface.h
FourWheelSteering::SteeringJoint::position
double position
Definition: four_wheel_steering.h:149
FourWheelSteering::jnt_pos_interface_
hardware_interface::PositionJointInterface jnt_pos_interface_
Definition: four_wheel_steering.h:135
hardware_interface::JointHandle
ros::Time
FourWheelSteering::jnt_state_interface_
hardware_interface::JointStateInterface jnt_state_interface_
Definition: four_wheel_steering.h:133
FourWheelSteering::getTime
ros::Time getTime() const
Definition: four_wheel_steering.h:62
FourWheelSteering::steering_joints_
struct FourWheelSteering::SteeringJoint steering_joints_[4]
FourWheelSteering::jnt_vel_interface_
hardware_interface::VelocityJointInterface jnt_vel_interface_
Definition: four_wheel_steering.h:134
FourWheelSteering::start_srv_
ros::ServiceServer start_srv_
Definition: four_wheel_steering.h:159
robot_hw.h
FourWheelSteering::FourWheelSteering
FourWheelSteering()
Definition: four_wheel_steering.h:27
FourWheelSteering::Joint::Joint
Joint()
Definition: four_wheel_steering.h:144
FourWheelSteering::Joint::velocity
double velocity
Definition: four_wheel_steering.h:140
FourWheelSteering::read
void read()
Definition: four_wheel_steering.h:65
DurationBase< Duration >::toSec
double toSec() const
hardware_interface::PositionJointInterface
FourWheelSteering::SteeringJoint::effort
double effort
Definition: four_wheel_steering.h:151
ros::Duration
FourWheelSteering::Joint::effort
double effort
Definition: four_wheel_steering.h:141
ros::NodeHandle
ros::Time::now
static Time now()
FourWheelSteering::SteeringJoint::velocity
double velocity
Definition: four_wheel_steering.h:150


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Fri May 24 2024 02:41:15