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
main.cpp
- Committer:
- MikeGray92
- Date:
- 2018-04-26
- Revision:
- 10:836e701d00a6
- Parent:
- 8:478f75c6109c
- Child:
- 14:97804177806d
File content as of revision 10:836e701d00a6:
/* * Code for the Module Microcontroller as part of the * Autonomous Camera Kart project. * Controls the Gimbal motors, raise and lower mechanism, * IMU sensor input, communication with the NUC onboard computer. */ // Library Includes #include <stdint.h> #include "mbed.h" #include <ros.h> #include <std_msgs/Empty.h> #include <std_msgs/Int32MultiArray.h> #include <BNO055.h> #include <initializations.h> #include <definitions.h> #include <prototypes.h> #include <Mx28.h> // Micro Module Declarations PwmOut liftSpeed(D10); // Normally D10 DigitalOut liftDirection(D11); DigitalIn button(USER_BUTTON); Ticker hallInt; Timer filter_hall1; Timer rosMode_Delay; DynamixelClass gimbal(57600, D7, D8, D2); InterruptIn eStop(D5); DigitalOut value0(D3); DigitalOut value1(D4); ros::NodeHandle nh; ros::Subscriber<std_msgs::Int32MultiArray> sub("module_command", &module_commandCB); // Global Variable struct fields control; struct fields rosInput; float liftDutyCycle = 0; volatile int currentPosition = 0; int prevPosition = 0; int stallcount = 0; bool rosFlag = 1; bool eStopFlag = 0; // Main Program int main() { // Initializations value0.write(1); value1.write(1); filter_hall1.start(); //Start Filtering Timer eStop.fall(&eStopOn); eStop.rise(&eStopOff); setupGimbal(); // Gimbal setupLift(); // Lift setupROSNode(nh, sub); // ROS Node Handle rosInput.mode = 0; // Main Loop while (1) { //LED Inputs value0.write(0); value1.write(0); //ROS Functions nh.spinOnce(); rosCheck(); // Lift Operation runLift(); //Run Gimbal runGimbal(); } }