|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
19 #ifndef DDS_ROS_BRIDGE_ROS_TELEMETRY_RAPID_TELEMETRY_H_
20 #define DDS_ROS_BRIDGE_ROS_TELEMETRY_RAPID_TELEMETRY_H_
26 #include "dds_ros_bridge/ros_sub_rapid_pub.h"
28 #include "ff_msgs/CameraState.h"
29 #include "ff_msgs/CameraStatesStamped.h"
31 #include "knDds/DdsTypedSupplier.h"
33 #include "rapidUtil/RapidHelper.h"
37 #include "dds_msgs/AstrobeeConstants.h"
38 #include "dds_msgs/TelemetryConfigSupport.h"
39 #include "dds_msgs/TelemetryStateSupport.h"
46 const std::string& pub_topic,
47 const ros::NodeHandle &nh,
49 unsigned int queue_size = 10);
67 kn::DdsTypedSupplier<rapid::ext::astrobee::TelemetryConfig>;
71 kn::DdsTypedSupplier<rapid::ext::astrobee::TelemetryState>;
80 #endif // DDS_ROS_BRIDGE_ROS_TELEMETRY_RAPID_TELEMETRY_H_
void SetSparseMappingPoseRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:169
void SetCommStatusRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:106
void SetDiskStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:124
rapid::ext::astrobee::CameraResolution ConvertResolution(std::string const &resolution)
Definition: ros_telemetry_rapid_telemetry.cc:263
void SetCpuStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:115
StateSupplierPtr state_supplier_
Definition: ros_telemetry_rapid_telemetry.h:75
bool AssembleConfig(config_reader::ConfigReader &config_params)
Definition: ros_telemetry_rapid_telemetry.cc:178
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
void SetPmcCmdStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:151
std::unique_ptr< StateSupplier > StateSupplierPtr
Definition: ros_telemetry_rapid_telemetry.h:72
void SetGncStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:142
Definition: ros_sub_rapid_pub.h:30
void SetEkfStateRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:133
void SetPositionRate(float rate)
Definition: ros_telemetry_rapid_telemetry.cc:160
Definition: generic_rapid_msg_ros_pub.h:36
kn::DdsTypedSupplier< rapid::ext::astrobee::TelemetryConfig > ConfigSupplier
Definition: ros_telemetry_rapid_telemetry.h:67
Definition: config_reader.h:48
kn::DdsTypedSupplier< rapid::ext::astrobee::TelemetryState > StateSupplier
Definition: ros_telemetry_rapid_telemetry.h:71
config_reader::ConfigReader config_params
Definition: fault_tester.cc:12
uint8_t state
Definition: signal_lights.h:90
ConfigSupplierPtr config_supplier_
Definition: ros_telemetry_rapid_telemetry.h:74
Definition: ros_telemetry_rapid_telemetry.h:43
std::unique_ptr< ConfigSupplier > ConfigSupplierPtr
Definition: ros_telemetry_rapid_telemetry.h:68
void CameraStateCallback(ff_msgs::CameraStatesStampedConstPtr const &state)
Definition: ros_telemetry_rapid_telemetry.cc:69