NASA Astrobee Robot Software
Astrobee Version:
develop
master
ros2
v0.17.0
v0.17.1
v0.17.2
v0.17.3
v0.18.0
v0.19.0
v0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
Main Page
Modules
•
All
Classes
Namespaces
Files
Functions
Variables
Typedefs
Enumerations
Enumerator
Friends
Macros
Pages
planner_trapezoidal.h
Go to the documentation of this file.
1
/* Copyright (c) 2017, United States Government, as represented by the
2
* Administrator of the National Aeronautics and Space Administration.
3
*
4
* All rights reserved.
5
*
6
* The Astrobee platform is licensed under the Apache License, Version 2.0
7
* (the "License"); you may not use this file except in compliance with the
8
* License. You may obtain a copy of the License at
9
*
10
* http://www.apache.org/licenses/LICENSE-2.0
11
*
12
* Unless required by applicable law or agreed to in writing, software
13
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15
* License for the specific language governing permissions and limitations
16
* under the License.
17
*/
18
19
#ifndef PLANNER_TRAPEZOIDAL_PLANNER_TRAPEZOIDAL_H_
20
#define PLANNER_TRAPEZOIDAL_PLANNER_TRAPEZOIDAL_H_
21
22
// Standard includes
23
#include <ros/ros.h>
24
25
// FSW includes
26
#include <
ff_util/ff_nodelet.h
>
27
#include <
ff_util/ff_flight.h
>
28
#include <
ff_common/ff_names.h
>
29
#include <
msg_conversions/msg_conversions.h
>
30
34
namespace
planner_trapezoidal
{
35
// Insert a trapezoid between two poses
36
void
InsertTrapezoid
(
ff_util::Segment
&segment,
ros::Time
& offset,
double
dt,
37
const
Eigen::Affine3d
& p0,
const
Eigen::Affine3d
& p1,
38
double
lin_v,
double
rot_v,
double
lin_a,
double
rot_a,
39
double
min_control_period,
double
epsilon);
40
41
}
42
#endif // PLANNER_TRAPEZOIDAL_PLANNER_TRAPEZOIDAL_H_
ff_flight.h
planner_trapezoidal
Definition:
planner_trapezoidal.h:34
ff_nodelet.h
planner_trapezoidal::InsertTrapezoid
void InsertTrapezoid(ff_util::Segment &segment, ros::Time &offset, double dt, const Eigen::Affine3d &p0, const Eigen::Affine3d &p1, double lin_v, double rot_v, double lin_a, double rot_a, double min_control_period, double epsilon)
Definition:
planner_trapezoidal.cc:97
ff_util::Segment
std::vector< Setpoint > Segment
Definition:
ff_flight.h:47
ff_names.h
optimization_common::Affine3d
Eigen::Affine3d Affine3d(const Eigen::Matrix< double, 7, 1 > &affine_vector)
Definition:
utilities.cc:43
msg_conversions.h
localization_common::Time
double Time
Definition:
time.h:23