armadillo2_hw.h
Go to the documentation of this file.
1 
2 #ifndef ARMADILLO2_HW_ARMADILLO_HW_H
3 #define ARMADILLO2_HW_ARMADILLO_HW_H
4 
5 #include "dxl_motors_builder.h"
6 #include "battery_pub.h"
7 #include "ricboard_pub.h"
8 #include "roboteq_diff_drive.h"
13 #include <std_msgs/String.h>
14 
15 
16 namespace armadillo2_hw
17 {
19  {
20  private:
21 
24 
25  /* interfaces */
31 
32  /* robot close loop components */
37 
39 
40  void registerInterfaces();
41  void straighHead();
42  void speakMsg(std::string msg, int sleep_time)
43  {
44  std_msgs::String speak_msg;
45  speak_msg.data = msg;
46  espeak_pub_.publish(speak_msg);
47  if (sleep_time > 0)
48  sleep(sleep_time);
49  }
50 
51  public:
52 
54  void read();
55  void write();
56  };
57 }
58 
59 #endif //ARMADILLO2_HW_ARMADILLO_HW_H
ArmadilloHW(ros::NodeHandle &nh)
void publish(const boost::shared_ptr< M > &message) const
hardware_interface::VelocityJointInterface velocity_interface_
Definition: armadillo2_hw.h:29
ros::Publisher espeak_pub_
Definition: armadillo2_hw.h:38
hardware_interface::PosVelJointInterface posvel_interface_
Definition: armadillo2_hw.h:28
hardware_interface::JointStateInterface joint_state_interface_
Definition: armadillo2_hw.h:26
RoboteqDiffDrive roboteq_
Definition: armadillo2_hw.h:36
DxlMotorsBuilder dxl_motors_
Definition: armadillo2_hw.h:33
hardware_interface::PositionJointInterface position_interface_
Definition: armadillo2_hw.h:27
hardware_interface::EffortJointInterface effort_interface_
Definition: armadillo2_hw.h:30
ros::NodeHandle * node_handle_
Definition: armadillo2_hw.h:23
void speakMsg(std::string msg, int sleep_time)
Definition: armadillo2_hw.h:42


armadillo2_hw
Author(s):
autogenerated on Wed Jan 3 2018 03:48:27