z1_controller/sim/IOROS.h

36 lines
1.2 KiB
C
Raw Normal View History

2022-07-20 11:11:38 +08:00
#ifndef IOROS_H
#define IOROS_H
#include <ros/ros.h>
#include "interface/IOInterface.h"
2022-11-11 19:49:41 +08:00
#include "message/MotorCmd.h"
#include "message/MotorState.h"
2022-07-20 11:11:38 +08:00
class IOROS : public IOInterface{
public:
2022-11-11 19:49:41 +08:00
IOROS();
2022-07-20 11:11:38 +08:00
~IOROS();
bool sendRecv(const LowlevelCmd *cmd, LowlevelState *state);
private:
ros::NodeHandle _nm;
std::string _rname; // robot_name retrieved from ROS parameter server
2022-07-20 11:11:38 +08:00
ros::Subscriber _servo_sub[7];
ros::Publisher _servo_pub[7];
unitree_legged_msgs::MotorState _joint_state[7];
unitree_legged_msgs::MotorCmd _joint_cmd[7];
void _sendCmd(const LowlevelCmd *cmd);
void _recvState(LowlevelState *state);
void _initRecv();
void _initSend();
void _joint00Callback(const unitree_legged_msgs::MotorState& msg);
void _joint01Callback(const unitree_legged_msgs::MotorState& msg);
void _joint02Callback(const unitree_legged_msgs::MotorState& msg);
void _joint03Callback(const unitree_legged_msgs::MotorState& msg);
void _joint04Callback(const unitree_legged_msgs::MotorState& msg);
void _joint05Callback(const unitree_legged_msgs::MotorState& msg);
void _gripperCallback(const unitree_legged_msgs::MotorState& msg);
};
#endif // IOROS_H