More changes to readme

This commit is contained in:
cesar 2022-03-07 11:17:20 -04:00
parent bc9b0207a4
commit f8ef230655
3 changed files with 40 additions and 2 deletions

2
.gitignore vendored
View File

@ -1,2 +1,2 @@
src/MoCap_*.py

View File

@ -135,3 +135,41 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
- number_elements: number of segments tether will be composed of - number_elements: number of segments tether will be composed of
- tl: segment length (should be no shorter than 0.3 meters) - tl: segment length (should be no shorter than 0.3 meters)
## ROS NODES
- LinkState.py determines payload load angles and their rates (theta and phi), as well as determines tether length and keeps track of variables needed in case of step test.
>> Publishes to:
/status/twoBody_status # localization and angles
/status/path_follow # boolean to run trajectory test
>> Subscribes to:
none
- ref_signalGen.py takes in desired position (xd) and determines smooth path trajectory.
>> Publishes to:
/reference/path # smooth path
/reference/flatsetpoint # needed to determine thrust
>> Subscribes to:
/status/twoBody_status
/mavros/local_position/velocity_body
/mavros/imu/data
/mavros/state
/reference/waypoints
- klausen_control.py determines forces on drone needed based on smooth path and feedback to dampen oscillations. From the forces needed, it publishes attitude commands.
>> Publishes to:
/command/quaternions # attitude commands
/reference/flatsetpoint # needed to determine thrust
>> Subscribes to:
/status/twoBody_status
/reference/path
/mavros/imu/data
/mavros/local_position/velocity_body
- node from mavros_controllers/geometric_controller subscribes to _/reference/flatsetpoint_ to determine thrust commands which are published to _command/bodyrate_command_ by default
- path_follow.cpp sets the vehicle in OFFBOARD mode (PX4) and takes off to a set height for 25 seconds before starting to publish attitude and thrust commands.
>> Publishes to:
mavros/setpoint_position/local # needed to hover @ set height
mavros/setpoint_raw/attitude # attitude and thrust commands
>> Subscribes to:
/command/quaternions
/command/bodyrate_command
/mavros/state

View File

@ -106,7 +106,7 @@ int main(int argc, char **argv)
ros::Subscriber thro_sub = nh.subscribe<mavros_msgs::AttitudeTarget> ros::Subscriber thro_sub = nh.subscribe<mavros_msgs::AttitudeTarget>
("command/bodyrate_command",10,thrust_cb); ("command/bodyrate_command",10,thrust_cb);
/********************** PULISHERS **********************/ /********************** PUBLISHERS **********************/
// Initiate publisher to publish commanded local position // Initiate publisher to publish commanded local position
ros::Publisher local_pos_pub = nh.advertise<geometry_msgs::PoseStamped> ros::Publisher local_pos_pub = nh.advertise<geometry_msgs::PoseStamped>
("mavros/setpoint_position/local", 10); ("mavros/setpoint_position/local", 10);