Go to the documentation of this file.
7 #include <std_msgs/Int32.h>
8 #include <std_msgs/Empty.h>
15 : name_(
"hardware_interface")
22 if (urdf_model == NULL)
29 std::size_t error = 0;
81 ROS_INFO(
"Initializing DiffBot Hardware Interface ...");
84 std::array<std::string, NUM_JOINTS> motor_names = {
"left_motor",
"right_motor"};
115 std::string pid_namespace =
"pid/" + motor_names[i];
131 ROS_INFO(
"... Done Initializing DiffBot Hardware Interface");
152 const int width = 10;
153 const char sep =
' ';
154 std::stringstream ss;
155 ss << std::left << std::setw(width) << std::setfill(sep) <<
"Read" << std::left << std::setw(width) << std::setfill(sep) <<
"ticks" << std::left << std::setw(width) << std::setfill(sep) <<
"angle" << std::left << std::setw(width) << std::setfill(sep) <<
"velocity" << std::endl;
156 ss << std::left << std::setw(width) << std::setfill(sep) <<
"j0:" << std::left << std::setw(width) << std::setfill(sep) <<
encoder_ticks_[0] << std::left << std::setw(width) << std::setfill(sep) <<
joint_positions_[0] << std::left << std::setw(width) << std::setfill(sep) <<
joint_velocities_[0] << std::endl;
157 ss << std::left << std::setw(width) << std::setfill(sep) <<
"j1:" << std::left << std::setw(width) << std::setfill(sep) <<
encoder_ticks_[1] << std::left << std::setw(width) << std::setfill(sep) <<
joint_positions_[1] << std::left << std::setw(width) << std::setfill(sep) << std::setfill(sep) <<
joint_velocities_[1];
194 std_msgs::Int32 left_motor;
195 std_msgs::Int32 right_motor;
204 left_motor.data = motor_cmds[0];
205 right_motor.data = motor_cmds[1];
232 const int width = 10;
233 const char sep =
' ';
234 std::stringstream ss;
236 ss << std::left << std::setw(width) << std::setfill(sep) <<
"Write"
237 << std::left << std::setw(width) << std::setfill(sep) <<
"velocity"
238 << std::left << std::setw(width) << std::setfill(sep) <<
"p_error"
239 << std::left << std::setw(width) << std::setfill(sep) <<
"i_error"
240 << std::left << std::setw(width) << std::setfill(sep) <<
"d_error"
241 << std::left << std::setw(width) << std::setfill(sep) <<
"pid out"
242 << std::left << std::setw(width) << std::setfill(sep) <<
"percent"
244 double p_error, i_error, d_error;
250 std::string j =
"j" + std::to_string(i) +
":";
251 ss << std::left << std::setw(width) << std::setfill(sep) << j
253 << std::left << std::setw(width) << std::setfill(sep) << p_error
254 << std::left << std::setw(width) << std::setfill(sep) << i_error
255 << std::left << std::setw(width) << std::setfill(sep) << d_error
256 << std::left << std::setw(width) << std::setfill(sep) << pid_outputs[i]
257 << std::left << std::setw(width) << std::setfill(sep) << motor_cmds[i]
266 ROS_INFO(
"Get number of measured joint states publishers");
270 ROS_INFO(
"Waiting for measured joint states being published...");
276 if (num_publishers == 0)
278 ROS_ERROR(
"No measured joint states publishers. Timeout reached.");
282 ROS_INFO_STREAM(
"Number of measured joint states publishers: " << num_publishers);
285 ROS_INFO(
"Publish /reset to encoders");
289 return (num_publishers > 0);
294 std::string urdf_string;
298 while (urdf_string.empty() &&
ros::ok())
300 std::string search_param_name;
332 std::stringstream ss;
333 std::cout.precision(15);
346 std::stringstream ss;
347 std::cout.precision(15);
348 ss <<
" position velocity effort \n";
hardware_interface::VelocityJointInterface velocity_joint_interface_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ros::Publisher pub_left_motor_value_
#define ROS_DEBUG_STREAM_NAMED(name, args)
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value)
bool getParam(const std::string &key, bool &b) const
void registerInterface(T *iface)
virtual void read(const ros::Time &time, const ros::Duration &period) override
Read data from the robot hardware.
_angular_velocities_type angular_velocities
virtual void write(const ros::Time &time, const ros::Duration &period)
Write commands to the robot hardware.
void init(ros::NodeHandle &nh, double f, double p, double i, double d, double i_max, double i_min, bool antiwindup, double out_max, double out_min)
Initialize the.
virtual void printState()
Helper for debugging a joint's state.
void setOutputLimits(double out_min, double out_max)
Set the Output Limits of the PID controller.
void encoderTicksCallback(const diffbot_msgs::EncodersStamped::ConstPtr &msg_encoders)
Callback to receive the encoder ticks from Teensy MCU.
hardware_interface::JointStateInterface joint_state_interface_
ros::Subscriber sub_measured_joint_states_
double linearToAngular(const double &distance) const
DiffBot reports travel distance in metres, need radians for ros_control RobotHW.
std::string printStateHelper()
virtual void loadURDF(const ros::NodeHandle &nh, std::string param_name)
Get the URDF XML from the parameter server.
std::string printCommandHelper()
Helper for debugging a joint's command.
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
ros::Subscriber sub_encoder_ticks_
ros::Publisher pub_right_motor_value_
uint32_t getNumPublishers() const
double joint_velocity_commands_[NUM_JOINTS]
JointState measured_joint_states_[NUM_JOINTS]
double angularToLinear(const double &angle) const
RobotHW provides velocity command in rad/s, DiffBot needs m/s.
double encoder_resolution_
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
The init function is called to initialize the RobotHW from a non-realtime thread.
DiffBotHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor.
#define ROS_INFO_STREAM_THROTTLE(period, args)
double normalizeAngle(double &angle) const
Normalize angle in the range of [0, 360)
#define ROS_ERROR_STREAM_NAMED(name, args)
bool searchParam(const std::string &key, std::string &result) const
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
double joint_velocities_[NUM_JOINTS]
ros::Publisher pub_reset_encoders_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
URDF_EXPORT bool initString(const std::string &xmlstring)
#define ROS_INFO_STREAM(args)
std::vector< std::string > joint_names_
int encoder_ticks_[NUM_JOINTS]
void registerHandle(const JointStateHandle &handle)
double joint_efforts_[NUM_JOINTS]
urdf::Model * urdf_model_
const unsigned int NUM_JOINTS
ros::Publisher pub_wheel_cmd_velocities_
void measuredJointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg_joint_states)
Callback to receive the measured joint states from Teensy MCU.
double joint_positions_[NUM_JOINTS]
_wheels_cmd_type wheels_cmd
#define ROS_INFO_STREAM_NAMED(name, args)
double ticksToAngle(const int &ticks) const
Convert number of encoder ticks to angle in radians.
const std::string & getNamespace() const
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
bool isReceivingMeasuredJointStates(const ros::Duration &timeout=ros::Duration(1))
Check if measured joint states (position and velocity) are received.
diffbot_base
Author(s):
autogenerated on Thu Sep 7 2023 02:35:23