mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
saved work
This commit is contained in:
@@ -10,17 +10,39 @@
|
||||
#ifndef SCOUT_SKID_STEER_HPP
|
||||
#define SCOUT_SKID_STEER_HPP
|
||||
|
||||
#include <string>
|
||||
|
||||
#include <geometry_msgs/Twist.h>
|
||||
#include <ros/ros.h>
|
||||
|
||||
#include <string>
|
||||
|
||||
namespace wescore {
|
||||
class ScoutSkidSteer {
|
||||
public:
|
||||
ScoutSkidSteer(std::string robot_name);
|
||||
ScoutSkidSteer(ros::NodeHandle *nh, std::string robot_name = "");
|
||||
|
||||
void SetupSubscription();
|
||||
|
||||
private:
|
||||
std::string robot_name;
|
||||
std::string robot_name_;
|
||||
std::string motor_fr_topic_;
|
||||
std::string motor_fl_topic_;
|
||||
std::string motor_rl_topic_;
|
||||
std::string motor_rr_topic_;
|
||||
std::string cmd_topic_;
|
||||
|
||||
const double SCOUT_WHEELBASE = 0.498;
|
||||
const double SCOUT_WHEEL_RADIUS = 0.16459;
|
||||
|
||||
ros::NodeHandle *nh_;
|
||||
|
||||
ros::Publisher motor_fr_pub_;
|
||||
ros::Publisher motor_fl_pub_;
|
||||
ros::Publisher motor_rl_pub_;
|
||||
ros::Publisher motor_rr_pub_;
|
||||
|
||||
ros::Subscriber cmd_sub_;
|
||||
|
||||
void TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg);
|
||||
};
|
||||
} // namespace wescore
|
||||
|
||||
|
||||
Reference in New Issue
Block a user