Class SlotcarCommon

Nested Relationships

Nested Types

Class Documentation

class SlotcarCommon

Public Types

using PathRequestCallback = std::function<void(const rmf_fleet_msgs::msg::PathRequest::SharedPtr)>

Public Functions

SlotcarCommon()
rclcpp::Logger logger() const
template<typename SdfPtrT>
void read_sdf(SdfPtrT &sdf)
void set_model_name(const std::string &model_name)
std::string model_name() const
void init_ros_node(const rclcpp::Node::SharedPtr node)
UpdateResult update(const Eigen::Isometry3d &pose, const std::vector<Eigen::Vector3d> &obstacle_positions, const double time)
bool emergency_stop(const std::vector<Eigen::Vector3d> &obstacle_positions, const Eigen::Vector3d &current_heading)
std::array<double, 2> calculate_control_signals(const std::array<double, 2> &curr_velocities, const std::pair<double, double> &displacements, const double dt, const double target_velocity_now = 0.0, const double target_velocity_at_dest = 0.0, const std::optional<double> &linear_speed_limit = std::nullopt) const
std::array<double, 2> calculate_joint_control_signals(const std::array<double, 2> &w_tire, const std::pair<double, double> &displacements, const double dt, const double target_linear_speed_now = 0.0, const double target_linear_speed_destination = 0.0, const std::optional<double> &linear_speed_limit = std::nullopt) const
void charge_state_cb(const std::string &name, bool selected)
void publish_robot_state(const double time)
Eigen::Vector3d get_lookahead_point() const
inline void set_path_request_callback(PathRequestCallback cb)

Public Members

bool display_markers = false
struct UpdateResult

Public Members

double v = 0.0
double w = 0.0
double target_linear_speed_now = 0.0
double target_linear_speed_destination = 0.0
std::optional<double> max_speed = std::nullopt