![]() |
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <ros/ros.h>#include <ff_msgs/FamCommand.h>#include <i2c/i2c_new.h>#include <cerrno>#include <cstring>#include <string>
Macros | |
| #define | ROS_NODE_NAME "fam_cmd_i2c" |
Functions | |
| uint8_t | checksum (uint8_t *buf, size_t len) |
| bool | Init (const ros::NodeHandle &nh) |
| uint16_t | DoubleToUInt16 (double value, double scale) |
| int16_t | DoubleToInt16 (double value, double scale) |
| void | CommandCallback (const ff_msgs::FamCommand::ConstPtr &msg) |
| void | Exit (int status) |
| int | main (int argc, char **argv) |
Variables | |
| std::string | frame_id_ = "fam_cmd_i2c" |
| std::string | topic_fam_cmd_ = "/fam" |
| std::string | i2c_bus_file_ = "/dev/i2c-2" |
| int | i2c_addr_ = 0x40 |
| int | i2c_retries_ = 3 |
| double | scale_ = 65535.0 |
| i2c::Bus::Ptr | i2c_bus_ |
| #define ROS_NODE_NAME "fam_cmd_i2c" |
| uint8_t checksum | ( | uint8_t * | buf, |
| size_t | len | ||
| ) |
| void CommandCallback | ( | const ff_msgs::FamCommand::ConstPtr & | msg | ) |
| int16_t DoubleToInt16 | ( | double | value, |
| double | scale | ||
| ) |
| uint16_t DoubleToUInt16 | ( | double | value, |
| double | scale | ||
| ) |
| void Exit | ( | int | status | ) |
| bool Init | ( | const ros::NodeHandle & | nh | ) |
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
| std::string frame_id_ = "fam_cmd_i2c" |
| int i2c_addr_ = 0x40 |
| i2c::Bus::Ptr i2c_bus_ |
| std::string i2c_bus_file_ = "/dev/i2c-2" |
| int i2c_retries_ = 3 |
| double scale_ = 65535.0 |
| std::string topic_fam_cmd_ = "/fam" |