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

auto reformatting from compiler #17

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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 @@ -22,8 +22,6 @@ struct AckermannSteeringCtrlParameters : public HeadingControllerParameters {
std::string asString() const override;
};



class AckermannSteeringController : public HeadingController {
public:
AckermannSteeringController() = default;
Expand Down
16 changes: 7 additions & 9 deletions pure_pursuit_core/src/AckermannSteeringController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,20 +14,18 @@
namespace pure_pursuit {

namespace {
const double kRadToDeg = 180.0 / M_PI;
const double kRadToDeg = 180.0 / M_PI;
}

std::string AckermannSteeringCtrlParameters::asString() const {
std::string ret = HeadingControllerParameters::asString() + "\n";
std::string ret = HeadingControllerParameters::asString() + "\n";

ret += "wheel base (m): " + std::to_string(wheelBase_) + "\n";
ret += "max steering angle magnitued (deg): "
+ std::to_string(kRadToDeg * maxSteeringAngleMagnitude_) + "\n";
ret += "max steering rate of change (deg/s): "
+ std::to_string(kRadToDeg * maxSteeringRateOfChange_) + "\n";
ret += "dt (sec): " + std::to_string(dt_) + "\n";
ret += "wheel base (m): " + std::to_string(wheelBase_) + "\n";
ret += "max steering angle magnitued (deg): " + std::to_string(kRadToDeg * maxSteeringAngleMagnitude_) + "\n";
ret += "max steering rate of change (deg/s): " + std::to_string(kRadToDeg * maxSteeringRateOfChange_) + "\n";
ret += "dt (sec): " + std::to_string(dt_) + "\n";

return ret;
return ret;
}

bool AckermannSteeringController::advanceImpl() {
Expand Down
17 changes: 7 additions & 10 deletions pure_pursuit_core/src/AdaptiveVelocityController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,16 +11,13 @@

namespace pure_pursuit {


std::string AdaptiveVelocityControllerParameters::asString() const{
std::string ret;
ret += "desired velocity (m/s): " + std::to_string(desiredVelocity_) + "\n";
ret += "distance to goal when braking starts (m): "
+ std::to_string(distanceToGoalWhenBrakingStarts_) + "\n";
ret += "max velocity rate of change (m/s2): "
+ std::to_string(maxVelocityRateOfChange_) + "\n";
ret += "timestep (sec): " + std::to_string(timestep_);
return ret;
std::string AdaptiveVelocityControllerParameters::asString() const {
std::string ret;
ret += "desired velocity (m/s): " + std::to_string(desiredVelocity_) + "\n";
ret += "distance to goal when braking starts (m): " + std::to_string(distanceToGoalWhenBrakingStarts_) + "\n";
ret += "max velocity rate of change (m/s2): " + std::to_string(maxVelocityRateOfChange_) + "\n";
ret += "timestep (sec): " + std::to_string(timestep_);
return ret;
}

bool AdaptiveVelocityController::computeVelocity() {
Expand Down
13 changes: 6 additions & 7 deletions pure_pursuit_core/src/ConstantVelocityController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,15 +9,14 @@

namespace pure_pursuit {

void ConstantVelocityController::updateDrivingDirection(DrivingDirection drivingDirection){
if (drivingDirection != drivingDirection_){
rateLimiter_.reset(0.0); // assumption is that the robot is at zero velocity when changing directions
std::cout << "reseting the velocity rate limiter" << std::endl;
}
drivingDirection_ = drivingDirection;
void ConstantVelocityController::updateDrivingDirection(DrivingDirection drivingDirection) {
if (drivingDirection != drivingDirection_) {
rateLimiter_.reset(0.0); // assumption is that the robot is at zero velocity when changing directions
std::cout << "reseting the velocity rate limiter" << std::endl;
}
drivingDirection_ = drivingDirection;
}


bool ConstantVelocityController::computeVelocity() {
switch (drivingDirection_) {
case DrivingDirection::FWD: {
Expand Down
19 changes: 8 additions & 11 deletions pure_pursuit_core/src/HeadingController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,14 @@
namespace pure_pursuit {

std::string HeadingControllerParameters::asString() const {
std::string ret;
ret += "Lookahead distance fwd: " + std::to_string(lookaheadDistanceFwd_)
+ "\n";
ret += "Lookahead distance bck: " + std::to_string(lookaheadDistanceBck_)
+ "\n";
ret += "Anchor distance fwd: " + std::to_string(anchorDistanceFwd_) + "\n";
ret += "Anchor distance bck: " + std::to_string(anchorDistanceBck_) + "\n";
ret += "dead zone width: " + std::to_string(deadZoneWidth_) + "\n";
ret += "avg filter current sample weight: "
+ std::to_string(avgFilgerCurrentSampleWeight_);
return ret;
std::string ret;
ret += "Lookahead distance fwd: " + std::to_string(lookaheadDistanceFwd_) + "\n";
ret += "Lookahead distance bck: " + std::to_string(lookaheadDistanceBck_) + "\n";
ret += "Anchor distance fwd: " + std::to_string(anchorDistanceFwd_) + "\n";
ret += "Anchor distance bck: " + std::to_string(anchorDistanceBck_) + "\n";
ret += "dead zone width: " + std::to_string(deadZoneWidth_) + "\n";
ret += "avg filter current sample weight: " + std::to_string(avgFilgerCurrentSampleWeight_);
return ret;
}

bool HeadingController::initialize() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,10 @@

#pragma once

#include <ros/ros.h>
#include "pure_pursuit_core/heading_control/AckermannSteeringController.hpp"
#include <dynamic_reconfigure/server.h>
#include <pure_pursuit_ros/PurePursuitConfig.h>

#include <ros/ros.h>
#include "pure_pursuit_core/heading_control/AckermannSteeringController.hpp"

namespace pure_pursuit {

Expand All @@ -23,8 +22,7 @@ class AckermannSteeringControllerRos : public AckermannSteeringController {
void setParameters(const AckermannSteeringCtrlParameters& parameters) override;

private:

void ddCallback(pure_pursuit_ros::PurePursuitConfig &config, uint32_t level);
void ddCallback(pure_pursuit_ros::PurePursuitConfig& config, uint32_t level);

void initRos();
bool advanceImpl() override;
Expand All @@ -47,11 +45,10 @@ class AckermannSteeringControllerRos : public AckermannSteeringController {
std::unique_ptr<dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitConfig>> ddServer_;
dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitConfig>::CallbackType ddCalback_;
pure_pursuit_ros::PurePursuitConfig ddConfig_;

};

void updateFromDD(const pure_pursuit_ros::PurePursuitConfig &config, AckermannSteeringCtrlParameters *param);
void updateDD(const AckermannSteeringCtrlParameters &param, pure_pursuit_ros::PurePursuitConfig *config);
void updateFromDD(const pure_pursuit_ros::PurePursuitConfig& config, AckermannSteeringCtrlParameters* param);
void updateDD(const AckermannSteeringCtrlParameters& param, pure_pursuit_ros::PurePursuitConfig* config);

std::unique_ptr<HeadingController> createAckermannSteeringControllerRos(const AckermannSteeringCtrlParameters& parameters,
ros::NodeHandle* nh);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,47 +7,37 @@

#pragma once

#include <ros/ros.h>
#include "pure_pursuit_core/velocity_control/AdaptiveVelocityController.hpp"
#include <dynamic_reconfigure/server.h>
#include <pure_pursuit_ros/PurePursuitAdaptiveVelConfig.h>

#include <ros/ros.h>
#include "pure_pursuit_core/velocity_control/AdaptiveVelocityController.hpp"

namespace pure_pursuit {

class AdaptiveVelocityControllerRos: public AdaptiveVelocityController {
using BASE = AdaptiveVelocityController;

public:
explicit AdaptiveVelocityControllerRos(ros::NodeHandle *nh);
void setParameters(const AdaptiveVelocityControllerParameters &parameters)
override;
class AdaptiveVelocityControllerRos : public AdaptiveVelocityController {
using BASE = AdaptiveVelocityController;

private:
public:
explicit AdaptiveVelocityControllerRos(ros::NodeHandle* nh);
void setParameters(const AdaptiveVelocityControllerParameters& parameters) override;

void ddCallback(pure_pursuit_ros::PurePursuitAdaptiveVelConfig &config,
uint32_t level);
void initRos();
private:
void ddCallback(pure_pursuit_ros::PurePursuitAdaptiveVelConfig& config, uint32_t level);
void initRos();

ros::NodeHandle *nh_;
ros::NodeHandle ddnh_;

boost::recursive_mutex ddMutex_;
std::unique_ptr<
dynamic_reconfigure::Server<
pure_pursuit_ros::PurePursuitAdaptiveVelConfig>> ddServer_;
dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitAdaptiveVelConfig>::CallbackType ddCalback_;
pure_pursuit_ros::PurePursuitAdaptiveVelConfig ddConfig_;
ros::NodeHandle* nh_;
ros::NodeHandle ddnh_;

boost::recursive_mutex ddMutex_;
std::unique_ptr<dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitAdaptiveVelConfig>> ddServer_;
dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitAdaptiveVelConfig>::CallbackType ddCalback_;
pure_pursuit_ros::PurePursuitAdaptiveVelConfig ddConfig_;
};

void updateFromDD(const pure_pursuit_ros::PurePursuitAdaptiveVelConfig &config,
AdaptiveVelocityControllerParameters *param);
void updateDD(const AdaptiveVelocityControllerParameters &param,
pure_pursuit_ros::PurePursuitAdaptiveVelConfig *config);

void updateFromDD(const pure_pursuit_ros::PurePursuitAdaptiveVelConfig& config, AdaptiveVelocityControllerParameters* param);
void updateDD(const AdaptiveVelocityControllerParameters& param, pure_pursuit_ros::PurePursuitAdaptiveVelConfig* config);

std::unique_ptr<LongitudinalVelocityController> createAdaptiveVelocityControllerRos(const AdaptiveVelocityControllerParameters& parameters,
ros::NodeHandle* nh);
ros::NodeHandle* nh);

} /* namespace pure_pursuit*/
76 changes: 34 additions & 42 deletions pure_pursuit_ros/src/AckermannSteeringControllerRos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,32 +14,29 @@
namespace pure_pursuit {

namespace {
const double kDegToRad = M_PI / 180.0;
const double kRadToDeg = 180.0 / M_PI;
}
const double kDegToRad = M_PI / 180.0;
const double kRadToDeg = 180.0 / M_PI;
} // namespace

AckermannSteeringControllerRos::AckermannSteeringControllerRos(ros::NodeHandle* nh) : BASE(), nh_(nh), ddnh_("ackerman_steering") {
ddServer_ = std::make_unique<dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitConfig>>(ddMutex_,ddnh_);
ddServer_ = std::make_unique<dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitConfig>>(ddMutex_, ddnh_);
initRos();
}


void AckermannSteeringControllerRos::ddCallback(pure_pursuit_ros::PurePursuitConfig &config, uint32_t level){
ddConfig_ = config;
updateFromDD(ddConfig_, &parameters_);
ROS_INFO("Reconfigure Request: \n %s",
parameters_.asString().c_str());
void AckermannSteeringControllerRos::ddCallback(pure_pursuit_ros::PurePursuitConfig& config, uint32_t level) {
ddConfig_ = config;
updateFromDD(ddConfig_, &parameters_);
ROS_INFO("Reconfigure Request: \n %s", parameters_.asString().c_str());
}

void AckermannSteeringControllerRos::setParameters(const AckermannSteeringCtrlParameters& parameters){
BASE::setParameters(parameters);
updateDD(parameters,&ddConfig_);
ddServer_->updateConfig(ddConfig_);
void AckermannSteeringControllerRos::setParameters(const AckermannSteeringCtrlParameters& parameters) {
BASE::setParameters(parameters);
updateDD(parameters, &ddConfig_);
ddServer_->updateConfig(ddConfig_);
}

void AckermannSteeringControllerRos::initRos() {

ddCalback_ = boost::bind(&AckermannSteeringControllerRos::ddCallback,this, _1, _2);
ddCalback_ = boost::bind(&AckermannSteeringControllerRos::ddCallback, this, _1, _2);
ddServer_->setCallback(ddCalback_);

lookaheadPointPub_ = nh_->advertise<visualization_msgs::Marker>("pure_pursuit_heading_control/lookahead_point", 1, true);
Expand Down Expand Up @@ -149,33 +146,28 @@ std::unique_ptr<HeadingController> createAckermannSteeringControllerRos(const Ac
return std::move(ctrl);
}

void updateFromDD(const pure_pursuit_ros::PurePursuitConfig &config, AckermannSteeringCtrlParameters *param){
param->lookaheadDistanceFwd_ = config.lookahead_fwd;
param->lookaheadDistanceBck_ = config.lookahead_bck;
param->anchorDistanceFwd_ = config.anchor_dist_fwd;
param->anchorDistanceBck_ = config.anchor_dist_bck;
param->deadZoneWidth_ = config.dead_zone_width;
param->avgFilgerCurrentSampleWeight_ = config.avg_filter_current_sample_weight;
param->maxSteeringAngleMagnitude_ = config.max_steering_angle_magnitude_in_deg * kDegToRad;
param->maxSteeringRateOfChange_ = config.max_steering_rate_of_change_in_deg_per_sec * kDegToRad;
param->wheelBase_ = config.wheel_base;


void updateFromDD(const pure_pursuit_ros::PurePursuitConfig& config, AckermannSteeringCtrlParameters* param) {
param->lookaheadDistanceFwd_ = config.lookahead_fwd;
param->lookaheadDistanceBck_ = config.lookahead_bck;
param->anchorDistanceFwd_ = config.anchor_dist_fwd;
param->anchorDistanceBck_ = config.anchor_dist_bck;
param->deadZoneWidth_ = config.dead_zone_width;
param->avgFilgerCurrentSampleWeight_ = config.avg_filter_current_sample_weight;
param->maxSteeringAngleMagnitude_ = config.max_steering_angle_magnitude_in_deg * kDegToRad;
param->maxSteeringRateOfChange_ = config.max_steering_rate_of_change_in_deg_per_sec * kDegToRad;
param->wheelBase_ = config.wheel_base;
}
void updateDD(const AckermannSteeringCtrlParameters &param,
pure_pursuit_ros::PurePursuitConfig *config) {
config->lookahead_fwd = param.lookaheadDistanceFwd_;
config->lookahead_fwd = param.lookaheadDistanceFwd_;
config->lookahead_bck = param.lookaheadDistanceBck_;
config->anchor_dist_fwd = param.anchorDistanceFwd_;
config->anchor_dist_bck = param.anchorDistanceBck_;
config->dead_zone_width = param.deadZoneWidth_;
config->avg_filter_current_sample_weight =
param.avgFilgerCurrentSampleWeight_;
config->max_steering_angle_magnitude_in_deg =kRadToDeg * param.maxSteeringAngleMagnitude_;
config->max_steering_rate_of_change_in_deg_per_sec = kRadToDeg * param.maxSteeringRateOfChange_;
config->wheel_base = param.wheelBase_;

void updateDD(const AckermannSteeringCtrlParameters& param, pure_pursuit_ros::PurePursuitConfig* config) {
config->lookahead_fwd = param.lookaheadDistanceFwd_;
config->lookahead_fwd = param.lookaheadDistanceFwd_;
config->lookahead_bck = param.lookaheadDistanceBck_;
config->anchor_dist_fwd = param.anchorDistanceFwd_;
config->anchor_dist_bck = param.anchorDistanceBck_;
config->dead_zone_width = param.deadZoneWidth_;
config->avg_filter_current_sample_weight = param.avgFilgerCurrentSampleWeight_;
config->max_steering_angle_magnitude_in_deg = kRadToDeg * param.maxSteeringAngleMagnitude_;
config->max_steering_rate_of_change_in_deg_per_sec = kRadToDeg * param.maxSteeringRateOfChange_;
config->wheel_base = param.wheelBase_;
}

} /* namespace pure_pursuit */
48 changes: 19 additions & 29 deletions pure_pursuit_ros/src/AdaptiveVelocityControllerRos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,52 +9,42 @@
#include "pure_pursuit_core/math.hpp"
#include "se2_visualization_ros/visualization_helpers.hpp"



namespace pure_pursuit {
AdaptiveVelocityControllerRos::AdaptiveVelocityControllerRos(ros::NodeHandle* nh) : BASE(), nh_(nh), ddnh_("adaptive_vel_controller") {
ddServer_ = std::make_unique<dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitAdaptiveVelConfig>>(ddMutex_,ddnh_);
ddServer_ = std::make_unique<dynamic_reconfigure::Server<pure_pursuit_ros::PurePursuitAdaptiveVelConfig>>(ddMutex_, ddnh_);
initRos();
}


void AdaptiveVelocityControllerRos::ddCallback(pure_pursuit_ros::PurePursuitAdaptiveVelConfig &config, uint32_t level){
ddConfig_ = config;
updateFromDD(ddConfig_, &parameters_);
ROS_INFO("Reconfigure Request: \n %s",
parameters_.asString().c_str());
void AdaptiveVelocityControllerRos::ddCallback(pure_pursuit_ros::PurePursuitAdaptiveVelConfig& config, uint32_t level) {
ddConfig_ = config;
updateFromDD(ddConfig_, &parameters_);
ROS_INFO("Reconfigure Request: \n %s", parameters_.asString().c_str());
}

void AdaptiveVelocityControllerRos::setParameters(const AdaptiveVelocityControllerParameters& parameters){
BASE::setParameters(parameters);
updateDD(parameters,&ddConfig_);
ddServer_->updateConfig(ddConfig_);
void AdaptiveVelocityControllerRos::setParameters(const AdaptiveVelocityControllerParameters& parameters) {
BASE::setParameters(parameters);
updateDD(parameters, &ddConfig_);
ddServer_->updateConfig(ddConfig_);
}

void AdaptiveVelocityControllerRos::initRos() {

ddCalback_ = boost::bind(&AdaptiveVelocityControllerRos::ddCallback,this, _1, _2);
ddCalback_ = boost::bind(&AdaptiveVelocityControllerRos::ddCallback, this, _1, _2);
ddServer_->setCallback(ddCalback_);

}

void updateFromDD(const pure_pursuit_ros::PurePursuitAdaptiveVelConfig &config, AdaptiveVelocityControllerParameters *param){

param->desiredVelocity_ = config.nominal_velocity;
param->maxVelocityRateOfChange_ = config.max_vel_rate_of_change;
param->distanceToGoalWhenBrakingStarts_ = config.distance_when_braking_starts;

void updateFromDD(const pure_pursuit_ros::PurePursuitAdaptiveVelConfig& config, AdaptiveVelocityControllerParameters* param) {
param->desiredVelocity_ = config.nominal_velocity;
param->maxVelocityRateOfChange_ = config.max_vel_rate_of_change;
param->distanceToGoalWhenBrakingStarts_ = config.distance_when_braking_starts;
}
void updateDD(const AdaptiveVelocityControllerParameters &param,
pure_pursuit_ros::PurePursuitAdaptiveVelConfig *config) {
config->distance_when_braking_starts = param.distanceToGoalWhenBrakingStarts_;
config->max_vel_rate_of_change = param.maxVelocityRateOfChange_;
config->nominal_velocity = param.desiredVelocity_;

void updateDD(const AdaptiveVelocityControllerParameters& param, pure_pursuit_ros::PurePursuitAdaptiveVelConfig* config) {
config->distance_when_braking_starts = param.distanceToGoalWhenBrakingStarts_;
config->max_vel_rate_of_change = param.maxVelocityRateOfChange_;
config->nominal_velocity = param.desiredVelocity_;
}

std::unique_ptr<LongitudinalVelocityController> createAdaptiveVelocityControllerRos(const AdaptiveVelocityControllerParameters& parameters,
ros::NodeHandle* nh) {
ros::NodeHandle* nh) {
auto ctrl = std::make_unique<AdaptiveVelocityControllerRos>(nh);
ctrl->setParameters(parameters);
return std::move(ctrl);
Expand Down
Loading