diff --git a/.clang-format b/.clang-format new file mode 100644 index 000000000..7af7c0f54 --- /dev/null +++ b/.clang-format @@ -0,0 +1,63 @@ +--- +BasedOnStyle: Google +AccessModifierOffset: -2 +ConstructorInitializerIndentWidth: 2 +AlignEscapedNewlinesLeft: false +AlignTrailingComments: true +AllowAllParametersOfDeclarationOnNextLine: false +AllowShortIfStatementsOnASingleLine: false +AllowShortLoopsOnASingleLine: false +AllowShortFunctionsOnASingleLine: None +AlwaysBreakTemplateDeclarations: true +AlwaysBreakBeforeMultilineStrings: true +BreakBeforeBinaryOperators: false +BreakBeforeTernaryOperators: false +BreakConstructorInitializersBeforeComma: true +BinPackParameters: true +ColumnLimit: 120 +ConstructorInitializerAllOnOneLineOrOnePerLine: true +DerivePointerBinding: false +PointerBindsToType: true +ExperimentalAutoDetectBinPacking: false +IndentCaseLabels: true +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: None +ObjCSpaceBeforeProtocolList: true +PenaltyBreakBeforeFirstCallParameter: 19 +PenaltyBreakComment: 60 +PenaltyBreakString: 1 +PenaltyBreakFirstLessLess: 1000 +PenaltyExcessCharacter: 1000 +PenaltyReturnTypeOnItsOwnLine: 90 +SpacesBeforeTrailingComments: 2 +Cpp11BracedListStyle: false +Standard: Auto +IndentWidth: 2 +TabWidth: 2 +UseTab: Never +IndentFunctionDeclarationAfterType: false +SpacesInParentheses: false +SpacesInAngles: false +SpaceInEmptyParentheses: false +SpacesInCStyleCastParentheses: false +SpaceAfterControlStatementKeyword: true +SpaceBeforeAssignmentOperators: true +ContinuationIndentWidth: 4 +SortIncludes: false +SpaceAfterCStyleCast: false + +# Configure each individual brace in BraceWrapping +BreakBeforeBraces: Custom + +# Control of individual brace wrapping cases +BraceWrapping: + AfterClass: true + AfterControlStatement: 'true' + AfterEnum: true + AfterFunction: true + AfterNamespace: true + AfterStruct: true + AfterUnion: true + BeforeCatch: true + BeforeElse: true + IndentBraces: false diff --git a/.github/workflows/uml.yml b/.github/workflows/uml.yml new file mode 100644 index 000000000..72f11d9f5 --- /dev/null +++ b/.github/workflows/uml.yml @@ -0,0 +1,19 @@ +name: generate plantuml +on: push +jobs: + generate_plantuml: + runs-on: ubuntu-latest + name: plantuml + steps: + - name: checkout + uses: actions/checkout@v1 + with: + fetch-depth: 1 + - name: plantuml + id: plantuml + uses: grassedge/generate-plantuml-action@v1.5 + with: + path: docs/UMLs + message: "Render PlantUML files" + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} \ No newline at end of file diff --git a/.gitignore b/.gitignore index 68802e703..3aa6090b3 100644 --- a/.gitignore +++ b/.gitignore @@ -6,7 +6,8 @@ .LSOverride # Icon must end with two \r -Icon +Icon + # Thumbnails ._* @@ -101,4 +102,8 @@ tags # python -*.pyc \ No newline at end of file +*.pyc + +# Jetbrains +.idea/ +*cmake-build-debug/ diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 000000000..5dc508125 --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,32 @@ +--- +repos: + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v2.3.0 + hooks: + - id: check-yaml + - id: check-xml + - id: check-json + - id: end-of-file-fixer + - id: trailing-whitespace + - id: check-added-large-files + + # Python + - repo: https://github.com/psf/black + rev: 22.10.0 + hooks: + - id: black + language: python + args: [--line-length=120] + + # C++ + - repo: https://github.com/pre-commit/mirrors-clang-format + rev: v17.0.3 + hooks: + - id: clang-format + +# # YAML - still bad support for comments in YAML files +# - repo: https://github.com/jumanjihouse/pre-commit-hook-yamlfmt +# rev: 0.2.1 # or other specific tag +# hooks: +# - id: yamlfmt +# args: [--mapping, '2', --sequence, '4', --offset, '2', --width, '120'] diff --git a/README.md b/README.md index f2f8df9de..7a38081be 100644 --- a/README.md +++ b/README.md @@ -22,5 +22,3 @@ catkin build ## Demo Please check instruction in [wiki](https://github.com/JSKAerialRobot/aerial_robot/wiki). - - diff --git a/aerial_robot_base/config/sensors/altmeter/baro.yaml b/aerial_robot_base/config/sensors/altimeter/baro.yaml similarity index 100% rename from aerial_robot_base/config/sensors/altmeter/baro.yaml rename to aerial_robot_base/config/sensors/altimeter/baro.yaml diff --git a/aerial_robot_base/config/sensors/altmeter/leddar_one.yaml b/aerial_robot_base/config/sensors/altimeter/leddar_one.yaml similarity index 100% rename from aerial_robot_base/config/sensors/altmeter/leddar_one.yaml rename to aerial_robot_base/config/sensors/altimeter/leddar_one.yaml diff --git a/aerial_robot_base/config/sensors/altmeter/sonar.yaml b/aerial_robot_base/config/sensors/altimeter/sonar.yaml similarity index 100% rename from aerial_robot_base/config/sensors/altmeter/sonar.yaml rename to aerial_robot_base/config/sensors/altimeter/sonar.yaml diff --git a/aerial_robot_control/include/aerial_robot_control/flight_navigation.h b/aerial_robot_control/include/aerial_robot_control/flight_navigation.h index 65ee522cc..266963257 100644 --- a/aerial_robot_control/include/aerial_robot_control/flight_navigation.h +++ b/aerial_robot_control/include/aerial_robot_control/flight_navigation.h @@ -26,7 +26,7 @@ namespace aerial_robot_navigation /* control frame */ enum control_frame { - WORLD_FRAME, /* global frame, e.g. NEU, mocap */ + WORLD_FRAME, /* global frame, e.g. ENU, mocap */ LOCAL_FRAME /* head frame which is identical with imu head direction */ }; diff --git a/aerial_robot_estimation/src/sensor/plane_detection.cpp b/aerial_robot_estimation/src/sensor/plane_detection.cpp index 317f27237..925adfcea 100644 --- a/aerial_robot_estimation/src/sensor/plane_detection.cpp +++ b/aerial_robot_estimation/src/sensor/plane_detection.cpp @@ -97,7 +97,7 @@ namespace sensor_plugin /* initialization */ if (getStatus() == Status::INACTIVE) { - // 1. check altmeter is initialized, and check the height + // 1. check altimeter is initialized, and check the height bool alt_initialized = false; for (const auto& handler: estimator_->getAltHandlers()) { if (handler->getStatus() == Status::ACTIVE) { diff --git a/aerial_robot_simulation/scripts/gazebo_control_bridge.py b/aerial_robot_simulation/scripts/gazebo_control_bridge.py index ca5943a5f..0aea67705 100755 --- a/aerial_robot_simulation/scripts/gazebo_control_bridge.py +++ b/aerial_robot_simulation/scripts/gazebo_control_bridge.py @@ -69,7 +69,7 @@ def init(self): init_values[group_name] = subgroup_init_values self.actuator_command_pubs[group_name] = actuator_command_pubs - # setup the control subcriber + # setup the control subscriber group_ctrl_topic_name = rospy.get_param("actuator_controller/" + group_name + "/ctrl_topic_name", group_name + "_ctrl") self.joint_ctrl_sub_ = rospy.Subscriber(group_ctrl_topic_name, JointState, self.actuatorSubGroupCtrlCallback, group_name) diff --git a/docs/UMLs/classes.puml b/docs/UMLs/classes.puml new file mode 100644 index 000000000..b144b306c --- /dev/null +++ b/docs/UMLs/classes.puml @@ -0,0 +1,102 @@ +@startuml +'https://plantuml.com/class-diagram + +set namespaceSeparator :: + +abstract class aerial_robot_control::ControlBase { + + ControlBase() + + ~ControlBase() + + initialize() + + update() + + activate() + + reset() +} + +abstract class aerial_robot_control::PoseLinearController extends aerial_robot_control::ControlBase { + + PoseLinearController() + + ~PoseLinearController() + + initialize() + + update() + + reset() +} + +class aerial_robot_control::FullyActuatedController extends aerial_robot_control::PoseLinearController { + + FullyActuatedController() + + ~FullyActuatedController() + + initialize() + + reset() + + controlCore() + + sendCmd() +} + +class aerial_robot_control::UnderActuatedController extends aerial_robot_control::PoseLinearController { + + UnderActuatedController() + + ~UnderActuatedController() + + initialize() + + reset() +} + +class aerial_robot_control::UnderActuatedLQIController extends aerial_robot_control::PoseLinearController { + + UnderActuatedLQIController() + + ~UnderActuatedLQIController() + + initialize() + + activate() +} + +class aerial_robot_control::UnderActuatedTiltedLQIController extends aerial_robot_control::UnderActuatedLQIController { + + UnderActuatedTiltedLQIController() + + ~UnderActuatedTiltedLQIController() + + initialize() + + activate() +} + +class aerial_robot_control::HydrusLQIController extends aerial_robot_control::UnderActuatedLQIController { + + HydrusLQIController() + + initialize() + + checkRobotModel() +} + +class aerial_robot_control::HydrusTiltedLQIController extends aerial_robot_control::UnderActuatedTiltedLQIController { + + HydrusTiltedLQIController() + + initialize() + + checkRobotModel() +} + +class aerial_robot_control::DragonLQIGimbalController extends aerial_robot_control::HydrusLQIController { + + DragonLQIGimbalController() + + ~DragonLQIGimbalController() + + initialize() + + update() + + reset() +} + +class aerial_robot_control::DragonFullVectoringController extends aerial_robot_control::PoseLinearController { + + DragonFullVectoringController() + + ~DragonFullVectoringController() + + initialize() +} + +namespace aerial_robot_control { + note "under-actuated multi-rotor (quad-rotor)" as ud_mr + note "hydrus (option)" as hy + note "fully-actuated multi-rotor (tilted hex-rotor)" as fu_mr + note "hydrus_xi (hex type)" as hy_xi + note "hydrus (non tilted)" as hy_nt + note "dragon" as dragon + note "hydrus (non tilted/ tilted)" as hy_all +} +UnderActuatedController .. ud_mr +UnderActuatedController .. hy +FullyActuatedController .. fu_mr +FullyActuatedController .. hy_xi +HydrusLQIController .. hy_nt +HydrusLQIController .. ud_mr +HydrusTiltedLQIController .. hy_all +DragonLQIGimbalController .. dragon +DragonFullVectoringController .. dragon + + + +'TODO: give a unique namespace to robot specific controllers + +@enduml diff --git a/docs/UMLs/classes.svg b/docs/UMLs/classes.svg new file mode 100644 index 000000000..1a7408e7c --- /dev/null +++ b/docs/UMLs/classes.svg @@ -0,0 +1 @@ +aerial_robot_controlControlBaseControlBase()~ControlBase()initialize()update()activate()reset()PoseLinearControllerPoseLinearController()~PoseLinearController()initialize()update()reset()FullyActuatedControllerFullyActuatedController()~FullyActuatedController()initialize()reset()controlCore()sendCmd()UnderActuatedControllerUnderActuatedController()~UnderActuatedController()initialize()reset()UnderActuatedLQIControllerUnderActuatedLQIController()~UnderActuatedLQIController()initialize()activate()UnderActuatedTiltedLQIControllerUnderActuatedTiltedLQIController()~UnderActuatedTiltedLQIController()initialize()activate()HydrusLQIControllerHydrusLQIController()initialize()checkRobotModel()HydrusTiltedLQIControllerHydrusTiltedLQIController()initialize()checkRobotModel()DragonLQIGimbalControllerDragonLQIGimbalController()~DragonLQIGimbalController()initialize()update()reset()DragonFullVectoringControllerDragonFullVectoringController()~DragonFullVectoringController()initialize()under-actuated multi-rotor (quad-rotor)hydrus (option)fully-actuated multi-rotor (tilted hex-rotor)hydrus_xi (hex type)hydrus (non tilted)dragonhydrus (non tilted/ tilted) \ No newline at end of file diff --git a/docs/UMLs/folder_structure.puml b/docs/UMLs/folder_structure.puml new file mode 100644 index 000000000..c8032c421 --- /dev/null +++ b/docs/UMLs/folder_structure.puml @@ -0,0 +1,123 @@ +@startuml +'https://plantuml.com/component-diagram + +'Legend +' - Blue: common packages +' - Orange: only for simulation +' - Green: only for real machine + +package "jsk_aerial_robot" { + +[aerial_robot_base] #LightBlue +note right of aerial_robot_base + * standalone core + - execute functions from following blocks +end note + +[aerial_robot_model] #LightBlue +note right of [aerial_robot_model] + * joint based modelling + - kinematics, statics, stability + - jacobian + - derive model class as ros plugin + - servo motor interface (bridge) +end note + +[aerial_robot_estimation] #LightBlue +note right of [aerial_robot_estimation] + * sensor fusion + - cog motion estimation + - sensor interface as ros plugin + - kalman filter as ros plugin +end note + +[aerial_robot_control] #LightBlue +note right of [aerial_robot_control] + * flight control / navigation + - control based on cog motion + - navigation for cog and joint motion + - derive control/navigation class as ros plugin +end note + +[aerial_robot_msgs] #LightBlue +note right of [aerial_robot_msgs] + * ros messages + - aerial_robot_msgs/XXXXX +end note + +[aerial_robot_base] -[hidden]-> [aerial_robot_model] +[aerial_robot_model] -[hidden]-> [aerial_robot_estimation] +[aerial_robot_estimation] -[hidden]-> [aerial_robot_control] +[aerial_robot_control] -[hidden]-> [aerial_robot_msgs] + +package "robots" { + + note right of "robots" + * derive class as plugin for: + - model from aerial_robot_model + - control from aerial_robot_control + - navigation from aerial_robot_control (option) + end note + + [hydrus] #LightBlue + note right of [hydrus] + - two dimensional multilinked type + - vertical thrust + end note + + [hydrus_xi] #LightBlue + note right of [hydrus_xi] + - two dimensional multilinked type + - 1D vectorable thrust + end note + + [dragon] #LightBlue + note right of [dragon] + - three dimensional multilinked type + - 2D vectorable thrust + end note + + [hydrus] -[hidden]-> [hydrus_xi] + [hydrus_xi] -[hidden]-> [dragon] +} + +[aerial_robot_simulation] #Orange +note right of [aerial_robot_simulation] + * interface for gazebo + - hardware interface + - controller interface as plugin +end note + +[aerial_robot_msgs] -[hidden]-> [aerial_robot_simulation] + + +package "aerial_robot_nerve" { + [spinal_ros_bridge] #LightGreen + note right of [spinal_ros_bridge] + * uart between ros and spinal + - rosserial based + end note + + [spinal] #LightGreen + note right of [spinal] + * project for stm32 mcu + - attitude estimation + - attitude control + - CAN comm with neuron + end note + + [neuron] #LightGreen + note right of [neuron] + * project for stm32 mcu + - sensor interface via GPIO + - actuator interface via GPIO + - CAN comm with spinal + end note + + [spinal_ros_bridge] -[hidden]-> [spinal] + [spinal] -[hidden]-> [neuron] +} + +} + +@enduml diff --git a/docs/UMLs/folder_structure.svg b/docs/UMLs/folder_structure.svg new file mode 100644 index 000000000..23315f8e5 --- /dev/null +++ b/docs/UMLs/folder_structure.svg @@ -0,0 +1 @@ +jsk_aerial_robotrobotsaerial_robot_nerveaerial_robot_basestandalone core- execute functions from following blocksaerial_robot_modeljoint based modelling- kinematics, statics, stability- jacobian- derive model class as ros plugin- servo motor interface (bridge)aerial_robot_estimationsensor fusion- cog motion estimation- sensor interface as ros plugin- kalman filter as ros pluginaerial_robot_controlflight control / navigation- control based on cog motion- navigation for cog and joint motion- derive control/navigation class as ros pluginaerial_robot_msgsros messages- aerial_robot_msgs/XXXXXaerial_robot_simulationinterface for gazebo- hardware interface- controller interface as pluginderive class as plugin for:- model from aerial_robot_model- control from aerial_robot_control- navigation from aerial_robot_control (option)hydrus- two dimensional multilinked type- vertical thrusthydrus_xi- two dimensional multilinked type- 1D vectorable thrustdragon- three dimensional multilinked type- 2D vectorable thrustspinal_ros_bridgeuart between ros and spinal- rosserial basedspinalproject for stm32 mcu- attitude estimation- attitude control- CAN comm with neuronneuronproject for stm32 mcu- sensor interface via GPIO- actuator interface via GPIO- CAN comm with spinal \ No newline at end of file diff --git a/docs/UMLs/system_config.puml b/docs/UMLs/system_config.puml new file mode 100644 index 000000000..4ad69da48 --- /dev/null +++ b/docs/UMLs/system_config.puml @@ -0,0 +1,74 @@ +@startuml +'https://plantuml.com/component-diagram + + +package "Class Member as Plugins" { + [robot_model_loader_("aerial_robot_model",\n "aerial_robot_model::RobotModel")] as model_plugin + [pluginlib::ClassLoader(aerial_robot_estimation",\n "sensor_plugin::SensorBase")] as sensor_plugin + [pluginlib::ClassLoader("kalman_filter",\n "kf_plugin::KalmanFilter"))] as kf_plugin + model_plugin -[hidden]-> sensor_plugin + sensor_plugin -[hidden]-> kf_plugin +} + +package "Load as Plugin" { + [navigator_loader_("aerial_robot_control",\n "aerial_robot_navigation::BaseNavigator")] as navigator_plugin + [controller_loader_("aerial_robot_control",\n "aerial_robot_control::ControlBase")] as controller_plugin + navigator_plugin -[hidden]-> controller_plugin +} + +component "aerial_robot_base" as base { + [ROS spinal (ros::AsyncSpinner)\n4 multi-thread to call callbacks] as ROS_Spinal + [*Timer Loop\lVoid mainFunc(const ros::TimerEvent & e)\l{\l navigator_->update();\l controller_->update();\l }] as TimerLoop + package Instance { + [robot_model_ros_] + [estimator_] + [navigator_] + [controller_] + } +} + +[servo_bridge] + +package "Simulation (Gazebo)" { + ["Hardware interface"] + ["Controller interfaces"] + ["Hardware interface"] -[hidden]-> ["Controller interfaces"] +} + +package "Real Machine" { + [spinal_ros_bridge] + [sensor interfaces] + [spinal] +} + +'Relationship + +model_plugin -> robot_model_ros_ +sensor_plugin -> estimator_ +kf_plugin -> estimator_ + +navigator_plugin -> navigator_ +controller_plugin -> controller_ + +robot_model_ros_ --> estimator_ +robot_model_ros_ --> navigator_ +robot_model_ros_ --> controller_ +estimator_ --> navigator_ +estimator_ --> controller_ +navigator_ --> controller_ + +navigator_ -> TimerLoop +controller_ -> TimerLoop + +Instance --> ROS_Spinal + +base <--> servo_bridge +base <--> spinal_ros_bridge +servo_bridge <--> spinal_ros_bridge +servo_bridge <--> "Simulation (Gazebo)" +spinal_ros_bridge <--> spinal +[sensor interfaces] --> base + +kf_plugin -[hidden]-> navigator_plugin + +@enduml diff --git a/docs/UMLs/system_config.svg b/docs/UMLs/system_config.svg new file mode 100644 index 000000000..e86d5a205 --- /dev/null +++ b/docs/UMLs/system_config.svg @@ -0,0 +1 @@ +Class Member as PluginsLoad as Pluginaerial_robot_baseInstanceSimulation (Gazebo)Real Machinerobot_model_loader_("aerial_robot_model","aerial_robot_model::RobotModel")pluginlib::ClassLoader(aerial_robot_estimation","sensor_plugin::SensorBase")pluginlib::ClassLoader("kalman_filter","kf_plugin::KalmanFilter"))navigator_loader_("aerial_robot_control","aerial_robot_navigation::BaseNavigator")controller_loader_("aerial_robot_control","aerial_robot_control::ControlBase")ROS spinal (ros::AsyncSpinner)4 multi-thread to call callbacksTimer LoopVoid mainFunc(const ros::TimerEvent & e){navigator_->update();controller_->update();}robot_model_ros_estimator_navigator_controller_Hardware interfaceController interfacesspinal_ros_bridgesensor interfacesspinalservo_bridge \ No newline at end of file diff --git a/docs/UMLs/workflow.puml b/docs/UMLs/workflow.puml new file mode 100644 index 000000000..38c4b358e --- /dev/null +++ b/docs/UMLs/workflow.puml @@ -0,0 +1,48 @@ +@startuml +'https://plantuml.com/sequence-diagram + +' Legend +' ->> means inner communication via variables +'-> means outer communication via ROS topics + +'for nested boxes +!pragma teoz true + +autonumber + +box Laptop #Khaki +participant RViz +participant Terminal +end box + +box "Onboard PC\n(Jetson NX)" #LightGreen +participant "Nav" as Nav +participant "Control" as Ctl +participant "Estimator" as Est +end box + +box Gazebo (Laptop) #Aliceblue + + box " MCU\n(STM32 H7)" #LightBlue + participant "Spinal/Control_Spawner" as Spinal + end box + + box Body #LightGray + participant "ESC&Servo" as ESC + end box + +end box + +Est ->> Est: 100Hz + +loop 40Hz + Est ->> Ctl: estimator_->getState() +end loop + +Nav ->> Ctl: target_pos/vel/acc +loop 10Hz + Ctl -> Spinal: qd/attitude\ngeometry_msgs/Vector3Stamped +end loop +Spinal -> ESC: PWM + +@enduml diff --git a/docs/UMLs/workflow.svg b/docs/UMLs/workflow.svg new file mode 100644 index 000000000..56fc47d67 --- /dev/null +++ b/docs/UMLs/workflow.svg @@ -0,0 +1 @@ +LaptopOnboard PC(Jetson NX)Gazebo (Laptop)MCU(STM32 H7)BodyRVizTerminalNavControlEstimatorSpinal/Control_SpawnerESC&ServoRVizTerminalNavControlEstimatorSpinal/Control_SpawnerESC&Servo1100Hzloop[40Hz]2estimator_->getState()3target_pos/vel/accloop[10Hz]4qd/attitudegeometry_msgs/Vector3Stamped5PWM \ No newline at end of file diff --git a/docs/about_our_system.md b/docs/about_our_system.md new file mode 100644 index 000000000..f2426b346 --- /dev/null +++ b/docs/about_our_system.md @@ -0,0 +1,108 @@ +# About Our System + +## Folder Structure + +![](./UMLs/folder_structure.svg) + +## System Config + +![](./UMLs/system_config.svg) + +## Class Diagram + +![](./UMLs/classes.svg) + +## Workflow + +![](./UMLs/workflow.svg) + +## File Structure + +### ./aerial_robot + +A ROS Package. A sum-up of all the packages in this repository. + +### ./aerial_robot_base + +A ROS Package. Aerial robot base class. It contains: +- bin: some bash commands +- config: parameters for sensors, including altimeter, gps, imu, and mocap. Stored in .yaml files. +- include: header files for the aerial_robot_base class. +- launch: launch files for some common functions, including joy_stick, mocap, and rtk_gps. +- scripts: python files for some common functions, including controlling the robot with a keyboard and calculating RMS error. +- src: source files for the aerial_robot_base class, loading plugins for robot_model, estimator, navigator and controller. + Define a main loop with main_rate and update navigator and controller subsequently. +- test: files for rostest, only hovering test. + +### ./aerial_robot_control + +A ROS Package with various plugins for control. It contains: +- cfg: python files for dynamic reconfigure, a tool to change parameters online. Include PID and LQI controllers. +- include: header files for the controller. +- plugins: controller plugins, including FullyActuatedController, UnderActuatedController, UnderActuatedLQIController, + and UnderActuatedTiltedLQIController. User can select one of them through parameters, which generally stored in FlightControl.yaml. +- scripts: python demo to test controller. +- src: source files for the controllers. + +### ./aerial_robot_estimation + +A ROS package with various plugins for sensor usage and state estimation. It contains: +- cfg: python files for dynamic reconfigure, including Kalman Filter. +- config: parameters for optical flow. +- include: header files for the estimator. +- launch: launch files for the optical flow. +- plugins: estimator plugins, including kf_plugins (choosing sensor fusion method), sensor_plugins (choosing sensors), + and and vision_nodelet. Parameters are generally stored in StateEstimation.yaml. +- src: source files for the estimator: kalman filter for sensor fusion, different sensors, and vision (optical flow only). + Sensors include altitude, gps, imu, mocap, plane_detection and visual odometry (VO). + +### ./aerial_robot_model + +A ROS package with various plugins for robot model, calculating kinematics from urdf parameters with KDL and publishing +tf info. It contains: +- include: header files for the robot model. +- launch: launch files for setting robot_description to rosparameter server, publishing joint state and tf info, and + visualizing the robot in rviz. +- nodes: don't know yet. Maybe lisp file? +- plugins: include multirotor_robot_model and underactuated_tilted_robot_model. +- script: a python file that converts cog and intertia parameters from 3D models. +- src: source files for computing kinematics automatically, communicating with servos, and publishing tf info. +- srv: a service for adding a new link to the robot model. +- test: test by comparing jacobians calculated by KDL and numerical method. + +### ./aerial_robot_msgs + +A ROS package defining message types for aerial robot, containing: state-based info, parameter-based info. + +### ./aerial_robot_nerve + +Program for low-level autopilot running on a STM32 MCU. Leverage STM32CubeMX to generate the code and rosserial to communicate +with ROS. + +### ./aerial_robot_simulation + +A ROS package with various plugins for simulation in Gazebo, simulating dynamics, sensor noise, and controller in the nerve module. It contains: +- config: parameters for simulation, including the parameters to simulating MoCap. Stored in .yaml files. +- gazebo_model: world files. +- include: header files for the simulation. +- launch: launch files for Gazebo-based simulation. +- scripts: gazebo_control_bridge.py +- src: source files for the simulation, including dynamics, sensor noise, and controller in the nerve module. +- xacro: sensor setting for spinal MCU + +### ./images + +Store images. + +### ./robots + +Include multiple ROS Packages. Each package is for one specific robot. Take mini_quadrotor as an example, it contains: +- config: the yaml files for the robot, including various parameters for the robot, such as the parameters for the + motors, controllers, rviz, simulation, and so on. +- launch: the launch files for the robot. Note that for each robot, there is a bringup.launch file in the launch + folder. The bringup.launch file will load parameters and launch other launch files, including motor, battery, state + fusion, control, navigation, and so on. +- test: files for rostest. Hovering test included. +- urdf: the urdf files for the robot, including the dae files (shape and inertial) for main_body, propeller, and a + battery. Based on these urdf files, the kinematic parameters of the whole body will be calculated through Kinematics + and Dynamics Library (KDL). The urdf files are also used for visualization in rviz and Gazebo. diff --git a/docs/beginning.md b/docs/beginning.md new file mode 100644 index 000000000..94b6c9c58 --- /dev/null +++ b/docs/beginning.md @@ -0,0 +1,5 @@ +# How to begin + +1. learn Markdown +2. learn Git +3. learn GitHub \ No newline at end of file diff --git a/docs/how_to_contribute.md b/docs/how_to_contribute.md new file mode 100644 index 000000000..e9dde7bef --- /dev/null +++ b/docs/how_to_contribute.md @@ -0,0 +1,19 @@ +# How to contribute + +## Contribute Process + +1. fork the original repository from https://github.com/jsk-ros-pkg/jsk_aerial_robot +2. develop your own feature in your forked repository +3. once you finish your development, make a pull request to the original repository +4. the original repository maintainer will review your pull request and merge it if it is OK + +## Code Style + +We use Clang-format to format the C++ code, and use black to format the Python code. +Pre-commit, the format plugin, will run automatically before each commit. The specific function has been written in +.pre-commit-config.yaml. To activate this plugin, please run the following command in terminal and root directory: + +```bash + pip3 install pre-commit + pre-commit install +``` diff --git a/robots/hydrus/launch/includes/default_mode_201907/sensors.launch.xml b/robots/hydrus/launch/includes/default_mode_201907/sensors.launch.xml index 44f74762c..1a9f255c5 100644 --- a/robots/hydrus/launch/includes/default_mode_201907/sensors.launch.xml +++ b/robots/hydrus/launch/includes/default_mode_201907/sensors.launch.xml @@ -31,7 +31,7 @@ - + diff --git a/robots/hydrus/launch/includes/old_model_tx2_rs_t265_201906/sensors.launch.xml b/robots/hydrus/launch/includes/old_model_tx2_rs_t265_201906/sensors.launch.xml index ddbbd976b..9575f4e01 100644 --- a/robots/hydrus/launch/includes/old_model_tx2_rs_t265_201906/sensors.launch.xml +++ b/robots/hydrus/launch/includes/old_model_tx2_rs_t265_201906/sensors.launch.xml @@ -42,7 +42,7 @@ - + diff --git a/robots/hydrus/launch/includes/old_model_tx2_zed_201810/sensors.launch.xml b/robots/hydrus/launch/includes/old_model_tx2_zed_201810/sensors.launch.xml index 72207da67..4a8c7bf68 100644 --- a/robots/hydrus/launch/includes/old_model_tx2_zed_201810/sensors.launch.xml +++ b/robots/hydrus/launch/includes/old_model_tx2_zed_201810/sensors.launch.xml @@ -38,7 +38,7 @@ - + diff --git a/robots/hydrus/launch/includes/tilt_10deg_15inch_202106/sensors.launch.xml b/robots/hydrus/launch/includes/tilt_10deg_15inch_202106/sensors.launch.xml index 44f74762c..1a9f255c5 100644 --- a/robots/hydrus/launch/includes/tilt_10deg_15inch_202106/sensors.launch.xml +++ b/robots/hydrus/launch/includes/tilt_10deg_15inch_202106/sensors.launch.xml @@ -31,7 +31,7 @@ - + diff --git a/robots/hydrus/launch/includes/tilt_10deg_201907/sensors.launch.xml b/robots/hydrus/launch/includes/tilt_10deg_201907/sensors.launch.xml index 44f74762c..1a9f255c5 100644 --- a/robots/hydrus/launch/includes/tilt_10deg_201907/sensors.launch.xml +++ b/robots/hydrus/launch/includes/tilt_10deg_201907/sensors.launch.xml @@ -31,7 +31,7 @@ - + diff --git a/robots/hydrus/launch/includes/tilt_20deg_201907/sensors.launch.xml b/robots/hydrus/launch/includes/tilt_20deg_201907/sensors.launch.xml index 44f74762c..1a9f255c5 100644 --- a/robots/hydrus/launch/includes/tilt_20deg_201907/sensors.launch.xml +++ b/robots/hydrus/launch/includes/tilt_20deg_201907/sensors.launch.xml @@ -31,7 +31,7 @@ - + diff --git a/robots/hydrus_xi/launch/includes/xavier201811/sensors.launch.xml b/robots/hydrus_xi/launch/includes/xavier201811/sensors.launch.xml index 6303570fc..9de1453cd 100644 --- a/robots/hydrus_xi/launch/includes/xavier201811/sensors.launch.xml +++ b/robots/hydrus_xi/launch/includes/xavier201811/sensors.launch.xml @@ -34,7 +34,7 @@ - + diff --git a/robots/hydrus_xi/launch/includes/xavier_hokuyo/sensors.launch.xml b/robots/hydrus_xi/launch/includes/xavier_hokuyo/sensors.launch.xml index d8b2a773a..5649bc371 100644 --- a/robots/hydrus_xi/launch/includes/xavier_hokuyo/sensors.launch.xml +++ b/robots/hydrus_xi/launch/includes/xavier_hokuyo/sensors.launch.xml @@ -35,7 +35,7 @@ - + diff --git a/robots/mini_quadrotor/README.md b/robots/mini_quadrotor/README.md new file mode 100644 index 000000000..a0514bf8a --- /dev/null +++ b/robots/mini_quadrotor/README.md @@ -0,0 +1,15 @@ +# Mini Quadrotor + +# How to use + +In one terminal, run + +`roslaunch mini_quadrotor bringup.launch real_machine:=false simulation:=True headless:=False` + +In another terminal, run + +`rosrun aerial_robot_base keyboard_command.py` + +In this terminal, input `r` to arm the quadrotor, then input `t` to takeoff. The quadrotor will takeoff and hover. + +Input `l` to land the quadrotor.