Class RobotState

Class Documentation

class bitbots_localization::RobotState

Sample state for a particle filter that localizes the Robot.

Public Functions

RobotState()
RobotState(double x, double y, double T)
Parameters
  • x – Position of the robot.

  • y – Position of the robot.

  • T – Orientaion of the robot in radians.

RobotState operator*(float factor) const
RobotState &operator+=(const RobotState &other)
double getXPos() const
double getYPos() const
double getTheta() const
double getSinTheta() const
double getCosTheta() const
void setXPos(double x)
void setYPos(double y)
void setTheta(double t)
void setSinTheta(double t)
void setCosTheta(double t)
double calcDistance(const RobotState &state) const
visualization_msgs::msg::Marker renderMarker(std::string n_space, std::string frame, rclcpp::Duration lifetime, std_msgs::msg::ColorRGBA color, rclcpp::Time stamp) const

Public Members

bool is_explorer_

Public Static Functions

static void convertParticleListToEigen(const std::vector<particle_filter::Particle<RobotState>*> &particle_list, Eigen::MatrixXd &matrix, const bool ignore_explorers)

Private Members

double m_XPos
double m_YPos
double m_SinTheta
double m_CosTheta