Skip to content

Commit

Permalink
Rename variables and improve doc
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed May 24, 2024
1 parent 4b7647d commit 7554553
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -130,11 +130,11 @@ class SteeringOdometry

/**
* \brief Updates the odometry class with latest velocity command
* \param linear Linear velocity [m/s]
* \param angular Angular velocity [rad/s]
* \param v_bx Linear velocity [m/s]
* \param omega_bz Angular velocity [rad/s]
* \param dt time difference to last call
*/
void update_open_loop(const double linear, const double angular, const double dt);
void update_open_loop(const double v_bx, const double omega_bz, const double dt);

/**
* \brief Set odometry type
Expand Down Expand Up @@ -186,8 +186,8 @@ class SteeringOdometry

/**
* \brief Calculates inverse kinematics for the desired linear and angular velocities
* \param v_bx Linear velocity of the robot in x_b-axis direction
* \param omega_bz Angular velocity of the robot around x_z-axis
* \param v_bx Desired linear velocity of the robot in x_b-axis direction
* \param omega_bz Desired angular velocity of the robot around x_z-axis
* \return Tuple of velocity commands and steering commands
*/
std::tuple<std::vector<double>, std::vector<double>> get_commands(
Expand Down
8 changes: 4 additions & 4 deletions steering_controllers_library/src/steering_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,14 +174,14 @@ bool SteeringOdometry::update_from_velocity(
return update_odometry(linear_velocity, angular_velocity, dt);
}

void SteeringOdometry::update_open_loop(const double linear, const double angular, const double dt)
void SteeringOdometry::update_open_loop(const double v_bx, const double omega_bz, const double dt)
{
/// Save last linear and angular velocity:
linear_ = linear;
angular_ = angular;
linear_ = v_bx;
angular_ = omega_bz;

/// Integrate odometry:
integrate_fk(linear, angular, dt);
integrate_fk(v_bx, omega_bz, dt);
}

void SteeringOdometry::set_wheel_params(double wheel_radius, double wheelbase, double wheel_track)
Expand Down

0 comments on commit 7554553

Please sign in to comment.