NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
ros_telemetry_rapid_telemetry.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 DDS_ROS_BRIDGE_ROS_TELEMETRY_RAPID_TELEMETRY_H_
20 #define DDS_ROS_BRIDGE_ROS_TELEMETRY_RAPID_TELEMETRY_H_
21 
22 #include <string>
23 
25 
26 #include "dds_ros_bridge/ros_sub_rapid_pub.h"
27 
28 #include "ff_msgs/CameraState.h"
29 #include "ff_msgs/CameraStatesStamped.h"
30 
31 #include "knDds/DdsTypedSupplier.h"
32 
33 #include "rapidUtil/RapidHelper.h"
34 
35 #include "ros/ros.h"
36 
37 #include "dds_msgs/AstrobeeConstants.h"
38 #include "dds_msgs/TelemetryConfigSupport.h"
39 #include "dds_msgs/TelemetryStateSupport.h"
40 
41 namespace ff {
42 
44  public:
45  RosTelemetryRapidTelemetry(const std::string& subscribe_topic,
46  const std::string& pub_topic,
47  const ros::NodeHandle &nh,
49  unsigned int queue_size = 10);
50 
51  void CameraStateCallback(ff_msgs::CameraStatesStampedConstPtr const& state);
52  void SetCommStatusRate(float rate);
53  void SetCpuStateRate(float rate);
54  void SetDiskStateRate(float rate);
55  void SetEkfStateRate(float rate);
56  void SetGncStateRate(float rate);
57  void SetPmcCmdStateRate(float rate);
58  void SetPositionRate(float rate);
59  void SetSparseMappingPoseRate(float rate);
60 
61  protected:
63 
64  rapid::ext::astrobee::CameraResolution ConvertResolution(std::string const&
65  resolution);
66  using ConfigSupplier =
67  kn::DdsTypedSupplier<rapid::ext::astrobee::TelemetryConfig>;
68  using ConfigSupplierPtr = std::unique_ptr<ConfigSupplier>;
69 
70  using StateSupplier =
71  kn::DdsTypedSupplier<rapid::ext::astrobee::TelemetryState>;
72  using StateSupplierPtr = std::unique_ptr<StateSupplier>;
73 
76 };
77 
78 } // end namespace ff
79 
80 #endif // DDS_ROS_BRIDGE_ROS_TELEMETRY_RAPID_TELEMETRY_H_
ff::RosTelemetryRapidTelemetry::SetSparseMappingPoseRate
void SetSparseMappingPoseRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:169
ff::RosTelemetryRapidTelemetry::SetCommStatusRate
void SetCommStatusRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:106
ff::RosTelemetryRapidTelemetry::SetDiskStateRate
void SetDiskStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:124
ff::RosTelemetryRapidTelemetry::ConvertResolution
rapid::ext::astrobee::CameraResolution ConvertResolution(std::string const &resolution)
Definition: ros_telemetry_rapid_telemetry.cc:263
ff::RosTelemetryRapidTelemetry::SetCpuStateRate
void SetCpuStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:115
ff::RosTelemetryRapidTelemetry::state_supplier_
StateSupplierPtr state_supplier_
Definition: ros_telemetry_rapid_telemetry.h:75
ff::RosTelemetryRapidTelemetry::AssembleConfig
bool AssembleConfig(config_reader::ConfigReader &config_params)
Definition: ros_telemetry_rapid_telemetry.cc:178
ff::RosTelemetryRapidTelemetry::RosTelemetryRapidTelemetry
RosTelemetryRapidTelemetry(const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, config_reader::ConfigReader &config_params, unsigned int queue_size=10)
Definition: ros_telemetry_rapid_telemetry.cc:23
ff::RosTelemetryRapidTelemetry::SetPmcCmdStateRate
void SetPmcCmdStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:151
ff::RosTelemetryRapidTelemetry::StateSupplierPtr
std::unique_ptr< StateSupplier > StateSupplierPtr
Definition: ros_telemetry_rapid_telemetry.h:72
ff::RosTelemetryRapidTelemetry::SetGncStateRate
void SetGncStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:142
ff::RosSubRapidPub
Definition: ros_sub_rapid_pub.h:30
ff::RosTelemetryRapidTelemetry::SetEkfStateRate
void SetEkfStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:133
ff::RosTelemetryRapidTelemetry::SetPositionRate
void SetPositionRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:160
ff
Definition: generic_rapid_msg_ros_pub.h:36
ff::RosTelemetryRapidTelemetry::ConfigSupplier
kn::DdsTypedSupplier< rapid::ext::astrobee::TelemetryConfig > ConfigSupplier
Definition: ros_telemetry_rapid_telemetry.h:67
config_reader::ConfigReader
Definition: config_reader.h:48
ff::RosTelemetryRapidTelemetry::StateSupplier
kn::DdsTypedSupplier< rapid::ext::astrobee::TelemetryState > StateSupplier
Definition: ros_telemetry_rapid_telemetry.h:71
config_reader.h
config_params
config_reader::ConfigReader config_params
Definition: fault_tester.cc:12
state
uint8_t state
Definition: signal_lights.h:90
ff::RosTelemetryRapidTelemetry::config_supplier_
ConfigSupplierPtr config_supplier_
Definition: ros_telemetry_rapid_telemetry.h:74
ff::RosTelemetryRapidTelemetry
Definition: ros_telemetry_rapid_telemetry.h:43
ff::RosTelemetryRapidTelemetry::ConfigSupplierPtr
std::unique_ptr< ConfigSupplier > ConfigSupplierPtr
Definition: ros_telemetry_rapid_telemetry.h:68
ff::RosTelemetryRapidTelemetry::CameraStateCallback
void CameraStateCallback(ff_msgs::CameraStatesStampedConstPtr const &state)
Definition: ros_telemetry_rapid_telemetry.cc:69