Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed ros_lib_kinetic
FreeFlyerHardware.h
- Committer:
- ambyld
- Date:
- 2018-06-29
- Revision:
- 4:cae255669971
- Parent:
- 1:40bdbe1a93b7
- Child:
- 5:864709d3eb76
File content as of revision 4:cae255669971:
#ifndef FREEFLYERHARDWARE_H
#define FREEFLYERHARDWARE_H
#include "mbed.h"
#include "math.h"
#include <ros.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Float32MultiArray.h>
#include "PID.h"
#include "QEI.h"
#include "defines.h"
#include "RGBA_LED.h"
#include "utilities.h"
#include <algorithm>
class FreeFlyerHardware
{
public:
FreeFlyerHardware(ros::NodeHandle &nh, I2C *i2c, DigitalOut *thruster_pinouts,
DigitalOut *led_inv_out_en, bool debug_flag);
void updatePID();
void commandThrusters(int *thruster_on_off_cmd); // switch to char for easy use?
void stepThrusterPWM();
void publishWheelMeas();
void publishPIDParam();
float getPWMOut();
void setPWMOut(float pwm_out);
void setPIDSetpoint(float pid_setpoint);
float duty_cycle_cmd_; // Only for duty cycle command mode
bool duty_cycle_command_mode_;
bool feed_forward_mode_;
RGBA_LED *rgba_led_;
QEI *wheel_encoder_; // object to interact with encoder outputs
protected:
int NUM_THRUSTERS;
PID *controller_;
int thruster_pwm_stop_[8]; // Number that the PWM count reaches before each thruster turns off
int thruster_pwm_clock_;
float shaft_vel_meas_; // [RPM] Measured shaft speed
float current_out_, voltage_out_, pwm_out_;
float slope_ff_, inter_ff_; // Feedforward slope, intercept terms
DigitalOut *thruster_pinouts_;
// ROS
ros::NodeHandle *root_nh_;
ros::Publisher *velocity_sns_pub_, *setpoint_pub_, *acc_error_pub_;
ros::Publisher *pid_param_pub_;
std_msgs::Float32 velocity_sns_msg_, setpoint_msg_, acc_error_msg_;
std_msgs::Float32MultiArray pid_param_msg_;
ros::Subscriber<std_msgs::Float32, FreeFlyerHardware> *wheel_vel_cmd_sub_,
*wheel_duty_cycle_cmd_sub_;
ros::Subscriber<std_msgs::Float32MultiArray, FreeFlyerHardware> *thruster_duty_cmd_sub_,
*wheel_pid_params_cmd_sub_;
void wheelVelCmdCallback(const std_msgs::Float32& msg);
void wheelDutyCycleCmdCallback(const std_msgs::Float32& msg);
void wheelPidParamsCmdCallback(const std_msgs::Float32MultiArray& msg);
void thrusterDutyCmdCallback(const std_msgs::Float32MultiArray& msg);
bool debug_flag_;
};
#endif