Skip to content

Commit

Permalink
Documentação (#4)
Browse files Browse the repository at this point in the history
Documentação do código por meio de comentários no estilo javadoc.
Sugestão de alguns pontos de mudança por meio de comentários TODO.
  • Loading branch information
felipepsaraiva authored Jan 13, 2020
1 parent e0a57b5 commit 5c4ca11
Show file tree
Hide file tree
Showing 17 changed files with 615 additions and 80 deletions.
44 changes: 39 additions & 5 deletions include/BodyServo.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,26 +5,60 @@
#include <config.h>
#include <utils/generic_functions.h>

/**
* A class that represents a servo in the body.
*/
class BodyServo {
private:
uint8_t cid;
uint8_t rid;
int16_t position;
int16_t offset;
bool reverse;
uint8_t cid; // The ID that comes from the gait control.
uint8_t rid; // Real ID of the servo.
int16_t position; // Position goal in degrees.
int16_t offset; // Position offset in degrees.
bool reverse; // Flags if the movement should be reversed.

public:
/**
* @param cid Gait Control ID.
* @param rid Real servo ID.
* @param position Initial position of the servo in degrees.
* @param offset Position offset in degrees.
* @param reverse If the movement should be reversed.
*/
explicit BodyServo(uint8_t cid,
uint8_t rid,
int16_t position = 0,
int16_t offset = 0,
bool reverse = false);
~BodyServo();

/**
* @return Gait control ID of this servo.
*/
uint8_t get_cid();

/**
* @return Real servo ID.
*/
uint8_t get_rid();

/**
* @return Position goal in degrees.
*/
int16_t get_position(void);

/**
* Calculates and returns the absolute position in servo units (between 0 and
* 1024).
*
* @return Absolute position in servo units.
*/
uint16_t get_abs_position(void);

/**
* Sets the goal position in degrees of this servo.
*
* @param pos Goal position in degrees.
*/
void set_position(int16_t pos);
};

Expand Down
9 changes: 9 additions & 0 deletions include/ControlStatus.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
#ifndef CONTROLSTATUS_H_
#define CONTROLSTATUS_H_

/**
* Enumeration of all possible states of the gait control.
*/
enum class ControlState {
Unknown = 0,
Idle = 1,
Expand All @@ -11,6 +14,12 @@ enum class ControlState {
Fallen = 6
};

/**
* Struct to group all information of the status of the gait control.
*
* @see RosCommunication#status
* @see control_status_callback(const std_msgs::UInt8MultiArray& msg)
*/
struct ControlStatus {
ControlState state;
bool is_mode_manual;
Expand Down
9 changes: 9 additions & 0 deletions include/DMASerial.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,19 @@
#include <libmaple/dma.h>
#include <libmaple/usart.h>

/**
* Enumaration of the DMA IRQ Handlers available.
*/
typedef enum {
DMA_IRQ_HANDLER_NONE = 0,
DMA_IRQ_HANDLER_1 = 1,
DMA_IRQ_HANDLER_2 = 2,
DMA_IRQ_HANDLER_3 = 3
} dma_irq_handler;

/**
* Class to encapsulate access of a UART through DMA using stm32 HAL.
*/
class DMASerial {
public:
DMASerial(dma_dev* dev,
Expand Down Expand Up @@ -44,6 +50,9 @@ class DMASerial {
bool transfering;
};

/**
* Class to handle DMA IRQs
*/
class DMAInterrupts {
public:
static DMASerial* serial1;
Expand Down
75 changes: 73 additions & 2 deletions include/RosCommunication.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,34 +10,105 @@
#include <std_msgs/UInt8MultiArray.h>
#include <utils/DelayTimer.h>

// TODO: Clear ros_lib to include only necessary msgs

/**
* Class that handles all communication with the computer through ros-serial.
*/
class RosCommunication {
public:
RosCommunication();

ros::NodeHandle nh;

/**
* String message used to publish the command topic.
* @see #publish_command(const char* cmd)
*/
std_msgs::String str_msg;

/**
* ROS publisher used to publish command messages.
* @see #publish_command(const char* cmd)
*/
ros::Publisher cmd_pub;

/**
* ROS subscriber that listens to the joint position messages.
*/
ros::Subscriber<std_msgs::Int16MultiArray> joint_pos_sub;

/**
* ROS subscriber that listens to the control status messages.
*/
ros::Subscriber<std_msgs::UInt8MultiArray> control_status_sub;

/**
* ROS subscriber that listens to the interpolate position messages.
*/
ros::Subscriber<std_msgs::Int16MultiArray> interpolate_sub;

/**
* Millis of when the last spin happened.
* @see #spin()
*/
time_t last_spin;

/**
* Flag to indicate if the node handle is connected to the computer ROS node.
* @see #check_connection()
*/
bool connected;

/**
* Gait control status received in the last "control_status" message.
* @see control_status_callback(const std_msgs::UInt8MultiArray& msg)
*/
ControlStatus status;

RosCommunication();

/**
* Sets the serial baud rate, setups the node handle, advertise the publishers
* and setup the subscribers.
*/
void setup();

/**
* Does a ros-serial spinOnce when it's time and update the last_spin member.
* @see ros::NodeHandle#spinOnce()
*/
void spin();

/**
* Checks if the connection on the node handle is active and update the
* peripheral led that indicates the connection status.
*/
void check_connection();

/**
* Publishes a command for the computer.
* @param cmd The command to be published.
*/
void publish_command(const char* cmd);
};

/**
* Global RosCommunication instance.
*/
extern RosCommunication control;

/**
* Callback executed when a joint position message is received.
*/
void joint_pos_callback(const std_msgs::Int16MultiArray& msg);

/**
* Callback executed when a control status message is received.
*/
void control_status_callback(const std_msgs::UInt8MultiArray& msg);

/**
* Callback executed when a interpolate position message is received.
*/
void interpolation_callback(const std_msgs::Int16MultiArray& msg);

#endif
Loading

0 comments on commit 5c4ca11

Please sign in to comment.