NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
fam.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 FAM_FAM_H_
20 #define FAM_FAM_H_
21 
22 #include <ros/node_handle.h>
23 #include <ros/publisher.h>
24 #include <ros/subscriber.h>
25 
26 #include <ff_msgs/FamCommand.h>
27 #include <ff_msgs/FlightMode.h>
28 
29 #include <ff_common/ff_names.h>
30 #include <ff_util/perf_timer.h>
31 
32 #include <Eigen/Dense>
33 #include <geometry_msgs/InertiaStamped.h>
34 
36 #include <pmc/fam.h>
37 
38 #include <mutex>
39 
40 namespace fam {
41 
45 class Fam {
46  public:
47  explicit Fam(ros::NodeHandle* nh);
48  ~Fam();
49  void Step();
50 
51  protected:
52  void ReadParams(void);
53  void CtlCallBack(const ff_msgs::FamCommand & c);
54  void FlightModeCallback(const ff_msgs::FlightMode::ConstPtr& mode);
55  void InertiaCallback(const geometry_msgs::InertiaStamped::ConstPtr& inertia);
56 
58 
59  ros::Subscriber ctl_sub_;
60  ros::Subscriber flight_mode_sub_, inertia_sub_;
61  ros::Publisher pmc_pub_;
62 
63  // config_reader::ConfigReader config_;
65  // ros::Timer config_timer_;
66 
67  std::mutex mutex_speed_;
68  std::mutex mutex_mass_;
69  Eigen::Vector3f center_of_mass_;
71 
73 };
74 } // end namespace fam
75 
76 #endif // FAM_FAM_H_
77 
mode
uint8_t mode
Definition: signal_lights.h:74
fam::Fam::fam_
pmc::Fam fam_
Definition: fam.h:57
fam::Fam::mutex_mass_
std::mutex mutex_mass_
Definition: fam.h:68
fam::Fam::inertia_received_
bool inertia_received_
Definition: fam.h:70
fam::Fam::pt_fam_
ff_util::PerfTimer pt_fam_
Definition: fam.h:64
fam::Fam::flight_mode_sub_
ros::Subscriber flight_mode_sub_
Definition: fam.h:60
fam::Fam::mutex_speed_
std::mutex mutex_speed_
Definition: fam.h:67
fam::Fam::Step
void Step()
Definition: fam.cc:73
perf_timer.h
fam::Fam::input_
pmc::FamInput input_
Definition: fam.h:72
fam::Fam
Force Allocation Module implementation using GNC module.
Definition: fam.h:45
fam::Fam::FlightModeCallback
void FlightModeCallback(const ff_msgs::FlightMode::ConstPtr &mode)
Definition: fam.cc:61
ff_util::PerfTimer
Definition: perf_timer.h:31
pmc::Fam
Definition: fam.h:33
fam::Fam::ctl_sub_
ros::Subscriber ctl_sub_
Definition: fam.h:59
fam::Fam::center_of_mass_
Eigen::Vector3f center_of_mass_
Definition: fam.h:69
fam::Fam::InertiaCallback
void InertiaCallback(const geometry_msgs::InertiaStamped::ConstPtr &inertia)
Definition: fam.cc:66
ff_names.h
pmc::FamInput
Definition: fam.h:26
fam::Fam::~Fam
~Fam()
Definition: fam.cc:52
fam::Fam::ReadParams
void ReadParams(void)
config_reader.h
fam::Fam::inertia_sub_
ros::Subscriber inertia_sub_
Definition: fam.h:60
fam::Fam::pmc_pub_
ros::Publisher pmc_pub_
Definition: fam.h:61
fam
Definition: fam.h:40
fam::Fam::Fam
Fam(ros::NodeHandle *nh)
Definition: fam.cc:31
fam::Fam::CtlCallBack
void CtlCallBack(const ff_msgs::FamCommand &c)
Definition: fam.cc:54
fam.h