mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
updated to use next branch of ugv_sdk
This commit is contained in:
@@ -1,9 +1,9 @@
|
||||
/*
|
||||
/*
|
||||
* scout_messenger.hpp
|
||||
*
|
||||
*
|
||||
* Created on: Jun 14, 2019 10:24
|
||||
* Description:
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||
*/
|
||||
|
||||
@@ -11,6 +11,7 @@
|
||||
#define SCOUT_MESSENGER_HPP
|
||||
|
||||
#include <string>
|
||||
#include <mutex>
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <nav_msgs/Odometry.h>
|
||||
@@ -18,57 +19,55 @@
|
||||
#include <tf2_ros/transform_broadcaster.h>
|
||||
|
||||
#include "scout_msgs/ScoutLightCmd.h"
|
||||
#include "ugv_sdk/scout_base.hpp"
|
||||
#include "ugv_sdk/mobile_robot/scout_robot.hpp"
|
||||
|
||||
namespace westonrobot
|
||||
{
|
||||
class ScoutROSMessenger
|
||||
{
|
||||
public:
|
||||
explicit ScoutROSMessenger(ros::NodeHandle *nh);
|
||||
ScoutROSMessenger(ScoutBase *scout, ros::NodeHandle *nh);
|
||||
namespace westonrobot {
|
||||
class ScoutROSMessenger {
|
||||
public:
|
||||
explicit ScoutROSMessenger(ros::NodeHandle *nh);
|
||||
ScoutROSMessenger(std::shared_ptr<ScoutRobot> scout, ros::NodeHandle *nh);
|
||||
|
||||
std::string odom_frame_;
|
||||
std::string base_frame_;
|
||||
std::string odom_topic_name_;
|
||||
std::string odom_frame_;
|
||||
std::string base_frame_;
|
||||
std::string odom_topic_name_;
|
||||
|
||||
bool simulated_robot_ = false;
|
||||
int sim_control_rate_ = 50;
|
||||
bool simulated_robot_ = false;
|
||||
int sim_control_rate_ = 50;
|
||||
|
||||
void SetupSubscription();
|
||||
void SetupSubscription();
|
||||
|
||||
void PublishStateToROS();
|
||||
void PublishSimStateToROS(double linear, double angular);
|
||||
void PublishStateToROS();
|
||||
void PublishSimStateToROS(double linear, double angular);
|
||||
|
||||
void GetCurrentMotionCmdForSim(double &linear, double &angular);
|
||||
void GetCurrentMotionCmdForSim(double &linear, double &angular);
|
||||
|
||||
private:
|
||||
ScoutBase *scout_;
|
||||
ros::NodeHandle *nh_;
|
||||
private:
|
||||
std::shared_ptr<ScoutRobot> scout_;
|
||||
ros::NodeHandle *nh_;
|
||||
|
||||
std::mutex twist_mutex_;
|
||||
geometry_msgs::Twist current_twist_;
|
||||
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_;
|
||||
tf2_ros::TransformBroadcaster tf_broadcaster_;
|
||||
ros::Publisher odom_publisher_;
|
||||
ros::Publisher status_publisher_;
|
||||
ros::Subscriber motion_cmd_subscriber_;
|
||||
ros::Subscriber light_cmd_subscriber_;
|
||||
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;
|
||||
// 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;
|
||||
|
||||
ros::Time last_time_;
|
||||
ros::Time current_time_;
|
||||
ros::Time last_time_;
|
||||
ros::Time current_time_;
|
||||
|
||||
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 TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg);
|
||||
void LightCmdCallback(const scout_msgs::ScoutLightCmd::ConstPtr &msg);
|
||||
void PublishOdometryToROS(double linear, double angular, double dt);
|
||||
};
|
||||
} // namespace westonrobot
|
||||
} // namespace westonrobot
|
||||
|
||||
#endif /* SCOUT_MESSENGER_HPP */
|
||||
|
||||
@@ -1,33 +1,33 @@
|
||||
/*
|
||||
/*
|
||||
* scout_params.hpp
|
||||
*
|
||||
*
|
||||
* Created on: Sep 27, 2019 15:08
|
||||
* Description:
|
||||
*
|
||||
* 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
|
||||
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
|
||||
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
|
||||
// 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 */
|
||||
|
||||
Reference in New Issue
Block a user