|
14 | 14 | // waypoints where constraints can also be applied. |
15 | 15 |
|
16 | 16 | int main() { |
17 | | - trajopt::DifferentialDrivetrain differentialDrivetrain{ |
| 17 | + trajopt::DifferentialDrivetrain differential_drivetrain{ |
18 | 18 | // kg |
19 | 19 | .mass = 45, |
20 | 20 | // kg-m² |
21 | 21 | .moi = 6, |
22 | 22 | // m |
23 | | - .wheelRadius = 0.08, |
| 23 | + .wheel_radius = 0.08, |
24 | 24 | // rad/s |
25 | | - .wheelMaxAngularVelocity = 70, |
| 25 | + .wheel_max_angular_velocity = 70, |
26 | 26 | // N-m |
27 | | - .wheelMaxTorque = 5, |
| 27 | + .wheel_max_torque = 5, |
28 | 28 | // unitless |
29 | | - .wheelCoF = 1.5, |
| 29 | + .wheel_cof = 1.5, |
30 | 30 | // m |
31 | 31 | .trackwidth = 0.6}; |
32 | 32 |
|
33 | | - trajopt::LinearVelocityMaxMagnitudeConstraint zeroLinearVelocity{0.0}; |
34 | | - trajopt::AngularVelocityMaxMagnitudeConstraint zeroAngularVelocity{0.0}; |
| 33 | + trajopt::LinearVelocityMaxMagnitudeConstraint zero_linear_velocity{0.0}; |
| 34 | + trajopt::AngularVelocityMaxMagnitudeConstraint zero_angular_velocity{0.0}; |
35 | 35 |
|
36 | 36 | // Example 1: Differential, one meter forward motion profile |
37 | 37 | { |
38 | 38 | trajopt::DifferentialPathBuilder path; |
39 | | - path.SetDrivetrain(differentialDrivetrain); |
40 | | - path.PoseWpt(0, 0.0, 0.0, 0.0); |
41 | | - path.PoseWpt(1, 1.0, 0.0, 0.0); |
42 | | - path.WptConstraint(0, zeroLinearVelocity); |
43 | | - path.WptConstraint(1, zeroLinearVelocity); |
44 | | - path.SetControlIntervalCounts({40}); |
| 39 | + path.set_drivetrain(differential_drivetrain); |
| 40 | + path.pose_wpt(0, 0.0, 0.0, 0.0); |
| 41 | + path.pose_wpt(1, 1.0, 0.0, 0.0); |
| 42 | + path.wpt_constraint(0, zero_linear_velocity); |
| 43 | + path.wpt_constraint(1, zero_linear_velocity); |
| 44 | + path.set_control_interval_counts({40}); |
45 | 45 |
|
46 | 46 | trajopt::DifferentialTrajectoryGenerator generator{path}; |
47 | 47 | [[maybe_unused]] |
48 | | - auto solution = generator.Generate(true); |
| 48 | + auto solution = generator.generate(true); |
49 | 49 | } |
50 | 50 |
|
51 | 51 | // Example 2: Differential, basic curve |
52 | 52 | { |
53 | 53 | trajopt::DifferentialPathBuilder path; |
54 | | - path.SetDrivetrain(differentialDrivetrain); |
55 | | - path.PoseWpt(0, 1.0, 1.0, -std::numbers::pi / 2); |
56 | | - path.PoseWpt(1, 2.0, 0.0, 0.0); |
57 | | - path.WptConstraint(0, zeroLinearVelocity); |
58 | | - path.WptConstraint(1, zeroLinearVelocity); |
59 | | - path.SetControlIntervalCounts({40}); |
| 54 | + path.set_drivetrain(differential_drivetrain); |
| 55 | + path.pose_wpt(0, 1.0, 1.0, -std::numbers::pi / 2); |
| 56 | + path.pose_wpt(1, 2.0, 0.0, 0.0); |
| 57 | + path.wpt_constraint(0, zero_linear_velocity); |
| 58 | + path.wpt_constraint(1, zero_linear_velocity); |
| 59 | + path.set_control_interval_counts({40}); |
60 | 60 |
|
61 | 61 | trajopt::DifferentialTrajectoryGenerator generator{path}; |
62 | 62 | [[maybe_unused]] |
63 | | - auto solution = generator.Generate(true); |
| 63 | + auto solution = generator.generate(true); |
64 | 64 | } |
65 | 65 |
|
66 | 66 | // Example 3: Differential, three waypoints |
67 | 67 | { |
68 | 68 | trajopt::DifferentialPathBuilder path; |
69 | | - path.SetDrivetrain(differentialDrivetrain); |
70 | | - path.PoseWpt(0, 0.0, 0.0, std::numbers::pi / 2); |
71 | | - path.PoseWpt(1, 1.0, 1.0, 0.0); |
72 | | - path.PoseWpt(2, 2.0, 0.0, std::numbers::pi / 2); |
73 | | - path.WptConstraint(0, zeroLinearVelocity); |
74 | | - path.WptConstraint(1, zeroLinearVelocity); |
75 | | - path.SetControlIntervalCounts({50, 50}); |
| 69 | + path.set_drivetrain(differential_drivetrain); |
| 70 | + path.pose_wpt(0, 0.0, 0.0, std::numbers::pi / 2); |
| 71 | + path.pose_wpt(1, 1.0, 1.0, 0.0); |
| 72 | + path.pose_wpt(2, 2.0, 0.0, std::numbers::pi / 2); |
| 73 | + path.wpt_constraint(0, zero_linear_velocity); |
| 74 | + path.wpt_constraint(1, zero_linear_velocity); |
| 75 | + path.set_control_interval_counts({50, 50}); |
76 | 76 |
|
77 | 77 | trajopt::DifferentialTrajectoryGenerator generator{path}; |
78 | 78 | [[maybe_unused]] |
79 | | - auto solution = generator.Generate(true); |
| 79 | + auto solution = generator.generate(true); |
80 | 80 | } |
81 | 81 |
|
82 | 82 | // Example 4: Differential, ending velocity |
83 | 83 | { |
84 | 84 | trajopt::DifferentialPathBuilder path; |
85 | | - path.SetDrivetrain(differentialDrivetrain); |
86 | | - path.PoseWpt(0, 0.0, 0.0, 0.0); |
87 | | - path.PoseWpt(1, 0.0, 1.0, 0.0); |
88 | | - path.WptConstraint(0, zeroLinearVelocity); |
89 | | - path.SetControlIntervalCounts({40}); |
| 85 | + path.set_drivetrain(differential_drivetrain); |
| 86 | + path.pose_wpt(0, 0.0, 0.0, 0.0); |
| 87 | + path.pose_wpt(1, 0.0, 1.0, 0.0); |
| 88 | + path.wpt_constraint(0, zero_linear_velocity); |
| 89 | + path.set_control_interval_counts({40}); |
90 | 90 |
|
91 | 91 | trajopt::DifferentialTrajectoryGenerator generator{path}; |
92 | 92 | [[maybe_unused]] |
93 | | - auto solution = generator.Generate(true); |
| 93 | + auto solution = generator.generate(true); |
94 | 94 | } |
95 | 95 |
|
96 | 96 | // Example 5: Differential, keep-out circle |
97 | 97 | { |
98 | 98 | trajopt::DifferentialPathBuilder path; |
99 | | - path.SetDrivetrain(differentialDrivetrain); |
100 | | - path.PoseWpt(0, 0.0, 0.0, 0.0); |
101 | | - trajopt::KeepOutRegion keepOut{// Radius of 0.1 |
102 | | - .safetyDistance = 0.1, |
103 | | - .points = {{0.5, 0.5}}}; |
104 | | - for (size_t i = 0; i < path.GetBumpers().at(0).points.size(); i++) { |
105 | | - path.SgmtConstraint(0, 1, |
106 | | - trajopt::PointPointMinConstraint{ |
107 | | - path.GetBumpers().at(0).points.at(i), |
108 | | - keepOut.points.at(0), keepOut.safetyDistance}); |
109 | | - path.SgmtConstraint( |
| 99 | + path.set_drivetrain(differential_drivetrain); |
| 100 | + path.pose_wpt(0, 0.0, 0.0, 0.0); |
| 101 | + trajopt::KeepOutRegion keep_out{// Radius of 0.1 |
| 102 | + .safety_distance = 0.1, |
| 103 | + .points = {{0.5, 0.5}}}; |
| 104 | + for (size_t i = 0; i < path.get_bumpers().at(0).points.size(); i++) { |
| 105 | + path.sgmt_constraint( |
| 106 | + 0, 1, |
| 107 | + trajopt::PointPointMinConstraint{ |
| 108 | + path.get_bumpers().at(0).points.at(i), keep_out.points.at(0), |
| 109 | + keep_out.safety_distance}); |
| 110 | + path.sgmt_constraint( |
110 | 111 | 0, 1, |
111 | 112 | trajopt::LinePointConstraint{ |
112 | | - path.GetBumpers().at(0).points.at(i), |
113 | | - path.GetBumpers().at(0).points.at( |
114 | | - (i + 1) % path.GetBumpers().at(0).points.size()), |
115 | | - keepOut.points.at(0), keepOut.safetyDistance}); |
| 113 | + path.get_bumpers().at(0).points.at(i), |
| 114 | + path.get_bumpers().at(0).points.at( |
| 115 | + (i + 1) % path.get_bumpers().at(0).points.size()), |
| 116 | + keep_out.points.at(0), keep_out.safety_distance}); |
116 | 117 | } |
117 | | - path.PoseWpt(1, 1.0, 0.0, 0.0); |
118 | | - path.WptConstraint(0, zeroLinearVelocity); |
119 | | - path.WptConstraint(1, zeroLinearVelocity); |
120 | | - path.SetControlIntervalCounts({40}); |
| 118 | + path.pose_wpt(1, 1.0, 0.0, 0.0); |
| 119 | + path.wpt_constraint(0, zero_linear_velocity); |
| 120 | + path.wpt_constraint(1, zero_linear_velocity); |
| 121 | + path.set_control_interval_counts({40}); |
121 | 122 |
|
122 | 123 | trajopt::DifferentialTrajectoryGenerator generator{path}; |
123 | 124 | [[maybe_unused]] |
124 | | - auto solution = generator.Generate(true); |
| 125 | + auto solution = generator.generate(true); |
125 | 126 | } |
126 | 127 |
|
127 | 128 | // Example 6: Approach a pick up station at a certain direction |
128 | 129 | { |
129 | 130 | trajopt::DifferentialPathBuilder path; |
130 | | - path.SetDrivetrain(differentialDrivetrain); |
| 131 | + path.set_drivetrain(differential_drivetrain); |
131 | 132 |
|
132 | 133 | // Starting position |
133 | | - path.PoseWpt(0, 0.0, 0.0, 0.0); |
| 134 | + path.pose_wpt(0, 0.0, 0.0, 0.0); |
134 | 135 |
|
135 | 136 | // Align towards the station one meter behind |
136 | | - path.PoseWpt(1, 1.0, 1.0, std::numbers::pi / 2); |
137 | | - path.WptConstraint(1, zeroAngularVelocity); |
138 | | - path.WptConstraint( |
| 137 | + path.pose_wpt(1, 1.0, 1.0, std::numbers::pi / 2); |
| 138 | + path.wpt_constraint(1, zero_angular_velocity); |
| 139 | + path.wpt_constraint( |
139 | 140 | 1, trajopt::LinearVelocityDirectionConstraint{std::numbers::pi / 2}); |
140 | 141 |
|
141 | 142 | // Go up to the station. In practice, the optimizer will still end up |
142 | 143 | // aligning the heading without the pose constraint since it's most optimal. |
143 | | - path.TranslationWpt(2, 1.0, 2.0); |
| 144 | + path.translation_wpt(2, 1.0, 2.0); |
144 | 145 |
|
145 | 146 | // Realign behind the station |
146 | | - path.PoseWpt(3, 1.0, 1.0, std::numbers::pi / 2); |
147 | | - path.WptConstraint(3, zeroAngularVelocity); |
148 | | - path.WptConstraint( |
| 147 | + path.pose_wpt(3, 1.0, 1.0, std::numbers::pi / 2); |
| 148 | + path.wpt_constraint(3, zero_angular_velocity); |
| 149 | + path.wpt_constraint( |
149 | 150 | 3, trajopt::LinearVelocityDirectionConstraint{std::numbers::pi / 2}); |
150 | 151 |
|
151 | 152 | // Ending position |
152 | | - path.PoseWpt(4, 2.0, 0.0, std::numbers::pi); |
| 153 | + path.pose_wpt(4, 2.0, 0.0, std::numbers::pi); |
153 | 154 |
|
154 | | - path.WptConstraint(0, zeroLinearVelocity); |
155 | | - path.WptConstraint(4, zeroLinearVelocity); |
156 | | - path.SetControlIntervalCounts({40, 30, 30, 40}); |
| 155 | + path.wpt_constraint(0, zero_linear_velocity); |
| 156 | + path.wpt_constraint(4, zero_linear_velocity); |
| 157 | + path.set_control_interval_counts({40, 30, 30, 40}); |
157 | 158 |
|
158 | 159 | trajopt::DifferentialTrajectoryGenerator generator{path}; |
159 | 160 | [[maybe_unused]] |
160 | | - auto solution = generator.Generate(true); |
| 161 | + auto solution = generator.generate(true); |
161 | 162 | } |
162 | 163 |
|
163 | 164 | // Example 7: Circular path with a point-point constraint |
164 | 165 | { |
165 | 166 | // Note that forcing a circular path is not a common problem in FRC. This |
166 | 167 | // example is only here to demonstrate how various constraints work. |
167 | 168 | trajopt::DifferentialPathBuilder path; |
168 | | - path.SetDrivetrain(differentialDrivetrain); |
169 | | - |
170 | | - path.PoseWpt(0, 0.0, 0.0, 0.0); |
171 | | - path.SgmtConstraint(0, 1, |
172 | | - trajopt::PointPointMinConstraint{ |
173 | | - // Robot point -- center of robot |
174 | | - {0.0, 0.0}, |
175 | | - // Field point around which to orbit |
176 | | - {1.0, 0.0}, |
177 | | - // Stay 1 m away to force circular motion |
178 | | - 1.0}); |
| 169 | + path.set_drivetrain(differential_drivetrain); |
| 170 | + |
| 171 | + path.pose_wpt(0, 0.0, 0.0, 0.0); |
| 172 | + path.sgmt_constraint(0, 1, |
| 173 | + trajopt::PointPointMinConstraint{ |
| 174 | + // Robot point -- center of robot |
| 175 | + {0.0, 0.0}, |
| 176 | + // Field point around which to orbit |
| 177 | + {1.0, 0.0}, |
| 178 | + // Stay 1 m away to force circular motion |
| 179 | + 1.0}); |
179 | 180 |
|
180 | 181 | // Tell optimizer to go in +y direction rather than -y |
181 | | - path.WptInitialGuessPoint(0, {0.0, 0.0, 0.0}); |
| 182 | + path.wpt_initial_guess_point(0, {0.0, 0.0, 0.0}); |
182 | 183 |
|
183 | | - path.PoseWpt(1, 2.0, 0.0, 0.0); |
| 184 | + path.pose_wpt(1, 2.0, 0.0, 0.0); |
184 | 185 |
|
185 | | - path.WptConstraint(0, zeroLinearVelocity); |
186 | | - path.WptConstraint(1, zeroLinearVelocity); |
187 | | - path.SetControlIntervalCounts({50}); |
| 186 | + path.wpt_constraint(0, zero_linear_velocity); |
| 187 | + path.wpt_constraint(1, zero_linear_velocity); |
| 188 | + path.set_control_interval_counts({50}); |
188 | 189 |
|
189 | 190 | trajopt::DifferentialTrajectoryGenerator generator{path}; |
190 | 191 | [[maybe_unused]] |
191 | | - auto solution = generator.Generate(true); |
| 192 | + auto solution = generator.generate(true); |
192 | 193 | } |
193 | 194 | } |
0 commit comments