Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Finish rename of nonholonomic to ackermann, make ackermann vehicles standardized with RMF stack #49

Merged
merged 5 commits into from
Sep 9, 2021
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@ namespace rmf_robot_sim_common {
// TODO migrate ign-math-eigen conversions when upgrading to ign-math5

//3rd coordinate is yaw
struct NonHolonomicTrajectory
struct AckermannTrajectory
{
NonHolonomicTrajectory(const Eigen::Vector2d& _x0, const Eigen::Vector2d& _x1,
AckermannTrajectory(const Eigen::Vector2d& _x0, const Eigen::Vector2d& _x1,
const Eigen::Vector2d& _v1 = Eigen::Vector2d(0, 0),
bool _turning = false)
: x0(_x0), x1(_x1),
Expand Down Expand Up @@ -130,6 +130,13 @@ enum class SteeringType
class SlotcarCommon
{
public:
typedef struct UpdateResult
luca-della-vedova marked this conversation as resolved.
Show resolved Hide resolved
{
double v = 0.0; // Target displacement in X (forward)
double w = 0.0; // Target displacement in yaw
double speed = 0.0; // Target speed
} UpdateResult;

SlotcarCommon();

rclcpp::Logger logger() const;
Expand All @@ -143,13 +150,10 @@ class SlotcarCommon

void init_ros_node(const rclcpp::Node::SharedPtr node);

std::pair<double, double> update(const Eigen::Isometry3d& pose,
UpdateResult update(const Eigen::Isometry3d& pose,
const std::vector<Eigen::Vector3d>& obstacle_positions,
const double time);

std::pair<double, double> update_nonholonomic(Eigen::Isometry3d& pose,
double& target_linear_velocity);

bool emergency_stop(const std::vector<Eigen::Vector3d>& obstacle_positions,
const Eigen::Vector3d& current_heading);

Expand All @@ -164,20 +168,10 @@ class SlotcarCommon
const std::pair<double, double>& displacements,
const double dt) const;

std::array<double, 2> calculate_model_control_signals(
const std::array<double, 2>& curr_velocities,
const std::pair<double, double>& displacements,
const double dt,
const double target_linear_velocity = 0.0) const;

void charge_state_cb(const std::string& name, bool selected);

void publish_robot_state(const double time);

SteeringType get_steering_type() const;

bool is_ackermann_steered() const;

private:
// Paramters needed for power dissipation and charging calculations
// Default values may be overriden using values from sdf file
Expand Down Expand Up @@ -218,15 +212,14 @@ class SlotcarCommon

std::vector<Eigen::Isometry3d> trajectory;
std::size_t _traj_wp_idx = 0;
std::vector<NonHolonomicTrajectory> nonholonomic_trajectory;
std::size_t _nonholonomic_traj_idx = 0;
std::vector<AckermannTrajectory> ackermann_trajectory;
std::size_t _ackermann_traj_idx = 0;

rmf_fleet_msgs::msg::PauseRequest pause_request;

std::vector<rclcpp::Time> _hold_times;

std::mutex _mutex;
std::mutex _ackmann_path_req_mutex;

std::string _model_name;
bool _emergency_stop = false;
Expand Down Expand Up @@ -317,7 +310,10 @@ class SlotcarCommon

void path_request_cb(const rmf_fleet_msgs::msg::PathRequest::SharedPtr msg);

void ackmann_path_request_cb(
void diff_drive_path_request_cb(
luca-della-vedova marked this conversation as resolved.
Show resolved Hide resolved
const rmf_fleet_msgs::msg::PathRequest::SharedPtr msg);

void ackermann_path_request_cb(
const rmf_fleet_msgs::msg::PathRequest::SharedPtr msg);

void pause_request_cb(const rmf_fleet_msgs::msg::PauseRequest::SharedPtr msg);
Expand All @@ -326,6 +322,14 @@ class SlotcarCommon

void map_cb(const rmf_building_map_msgs::msg::BuildingMap::SharedPtr msg);

UpdateResult update_diff_drive(const Eigen::Isometry3d& pose,
const std::vector<Eigen::Vector3d>& obstacle_positions,
const double time);

UpdateResult update_ackermann(const Eigen::Isometry3d& pose,
const std::vector<Eigen::Vector3d>& obstacle_positions,
const double time);

bool near_charger(const Eigen::Isometry3d& pose) const;

double compute_charge(const double run_time) const;
Expand Down
Loading