messenger: cleaned up messenger interface

This commit is contained in:
Ruixiang Du
2021-10-05 16:54:36 +08:00
parent 117f8def26
commit 7d9f027137
5 changed files with 172 additions and 110 deletions

View File

@@ -22,10 +22,22 @@
#include "ugv_sdk/mobile_robot/scout_robot.hpp"
namespace westonrobot {
class ScoutROSMessenger {
class ScoutMessenger {
public:
explicit ScoutROSMessenger(ros::NodeHandle *nh);
ScoutROSMessenger(std::shared_ptr<ScoutRobot> scout, ros::NodeHandle *nh);
explicit ScoutMessenger(ros::NodeHandle *nh);
ScoutMessenger(std::shared_ptr<ScoutRobot> scout, ros::NodeHandle *nh);
void SetOdometryFrame(std::string frame);
void SetBaseFrame(std::string frame);
void SetOdometryTopicName(std::string name);
void SetSimulationMode(int loop_rate);
void Run();
void Stop();
private:
std::shared_ptr<ScoutRobot> scout_;
ros::NodeHandle *nh_;
std::string odom_frame_;
std::string base_frame_;
@@ -34,29 +46,20 @@ class ScoutROSMessenger {
bool simulated_robot_ = false;
int sim_control_rate_ = 50;
void SetupSubscription();
void PublishStateToROS();
void PublishSimStateToROS(double linear, double angular);
void GetCurrentMotionCmdForSim(double &linear, double &angular);
private:
std::shared_ptr<ScoutRobot> scout_;
ros::NodeHandle *nh_;
std::atomic<bool> keep_running_;
std::mutex twist_mutex_;
geometry_msgs::Twist current_twist_;
ros::Publisher odom_publisher_;
ros::Publisher status_publisher_;
ros::Subscriber motion_cmd_subscriber_;
ros::Subscriber light_cmd_subscriber_;
ros::Publisher odom_pub_;
ros::Publisher status_pub_;
ros::Subscriber motion_cmd_sub_;
ros::Subscriber light_cmd_sub_;
tf2_ros::TransformBroadcaster tf_broadcaster_;
// speed variables
double linear_speed_ = 0.0;
double angular_speed_ = 0.0;
double position_x_ = 0.0;
double position_y_ = 0.0;
double theta_ = 0.0;
@@ -64,9 +67,15 @@ class ScoutROSMessenger {
ros::Time last_time_;
ros::Time current_time_;
void SetupSubscription();
void TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg);
void LightCmdCallback(const scout_msgs::ScoutLightCmd::ConstPtr &msg);
void PublishOdometryToROS(double linear, double angular, double dt);
void PublishStateToROS();
void PublishSimStateToROS(double linear, double angular);
void GetCurrentMotionCmdForSim(double &linear, double &angular);
};
} // namespace westonrobot

View File

@@ -1,33 +0,0 @@
/*
* scout_params.hpp
*
* Created on: Sep 27, 2019 15:08
* Description:
*
* Copyright (c) 2020 Ruixiang Du (rdu)
*/
#ifndef SCOUT_PARAMS_HPP
#define SCOUT_PARAMS_HPP
namespace westonrobot {
struct ScoutParams {
/* Scout Parameters */
static constexpr double max_steer_angle = 30.0; // in degree
static constexpr double track =
0.58306; // in meter (left & right wheel distance)
static constexpr double wheelbase =
0.498; // in meter (front & rear wheel distance)
static constexpr double wheel_radius = 0.165; // in meter
// from user manual v1.2.8 P18
// max linear velocity: 1.5 m/s
// max angular velocity: 0.7853 rad/s
static constexpr double max_linear_speed = 1.5; // in m/s
static constexpr double max_angular_speed = 0.7853; // in rad/s
static constexpr double max_speed_cmd = 10.0; // in rad/s
};
} // namespace westonrobot
#endif /* SCOUT_PARAMS_HPP */