Henry Speiser | 0b9b005 | 2022-03-02 23:07:40 -0800 | [diff] [blame] | 1 | #include "gflags/gflags.h" |
| 2 | #include "glog/logging.h" |
Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 3 | |
| 4 | #include "aos/events/shm_event_loop.h" |
| 5 | #include "aos/init.h" |
Henry Speiser | 0b9b005 | 2022-03-02 23:07:40 -0800 | [diff] [blame] | 6 | #include "y2022/setpoint_generated.h" |
| 7 | |
Milind Upadhyay | 9cb1421 | 2022-03-11 21:42:35 -0800 | [diff] [blame] | 8 | DEFINE_double(catapult_position, 0.03, "Catapult shot position"); |
| 9 | DEFINE_double(catapult_velocity, 18.0, "Catapult shot velocity"); |
Henry Speiser | 0b9b005 | 2022-03-02 23:07:40 -0800 | [diff] [blame] | 10 | DEFINE_double(turret, 0.0, "Turret setpoint"); |
| 11 | |
James Kuszmaul | 1f6099e | 2022-03-12 18:25:59 -0800 | [diff] [blame] | 12 | DEFINE_string(config, "aos_config.json", "Path to the config file to use."); |
| 13 | |
Henry Speiser | 0b9b005 | 2022-03-02 23:07:40 -0800 | [diff] [blame] | 14 | using y2022::input::joysticks::Setpoint; |
| 15 | |
| 16 | int main(int argc, char **argv) { |
| 17 | aos::InitGoogle(&argc, &argv); |
| 18 | |
| 19 | aos::FlatbufferDetachedBuffer<aos::Configuration> config = |
James Kuszmaul | 1f6099e | 2022-03-12 18:25:59 -0800 | [diff] [blame] | 20 | aos::configuration::ReadConfig(FLAGS_config); |
Henry Speiser | 0b9b005 | 2022-03-02 23:07:40 -0800 | [diff] [blame] | 21 | |
| 22 | aos::ShmEventLoop event_loop(&config.message()); |
| 23 | |
| 24 | auto setpoint_sender = event_loop.MakeSender<Setpoint>("/superstructure"); |
| 25 | |
| 26 | aos::Sender<Setpoint>::Builder builder = setpoint_sender.MakeBuilder(); |
| 27 | |
| 28 | Setpoint::Builder setpoint_builder = builder.MakeBuilder<Setpoint>(); |
| 29 | |
| 30 | setpoint_builder.add_catapult_position(FLAGS_catapult_position); |
| 31 | setpoint_builder.add_catapult_velocity(FLAGS_catapult_velocity); |
| 32 | setpoint_builder.add_turret(FLAGS_turret); |
| 33 | builder.CheckOk(builder.Send(setpoint_builder.Finish())); |
| 34 | |
| 35 | return 0; |
| 36 | } |