00001 // 00002 // Created by tom on 16/05/16. 00003 // 00004 00005 #include <robotican_hardware_interface/Switch.h> 00006 00007 void robotican_hardware::Switch::update(const DeviceMessage* deviceMessage) { 00008 if(isReady()) { 00009 SwitchFeedback *feedback = (SwitchFeedback *) deviceMessage; 00010 std_msgs::Bool state; 00011 state.data = feedback->state; 00012 _switchState.publish(state); 00013 } 00014 } 00015 00016 void robotican_hardware::Switch::write() { 00017 00018 } 00019 00020 void robotican_hardware::Switch::buildDevice() { 00021 BuildSwitch buildSwitch; 00022 buildSwitch.length = sizeof(buildSwitch); 00023 buildSwitch.checkSum = 0; 00024 buildSwitch.id = getId(); 00025 buildSwitch.pin = _pin; 00026 00027 uint8_t *rawData = (uint8_t*) &buildSwitch; 00028 buildSwitch.checkSum = _transportLayer->calcChecksum(rawData, buildSwitch.length); 00029 _transportLayer->write(rawData, buildSwitch.length); 00030 00031 } 00032 00033 robotican_hardware::Switch::Switch(byte id, TransportLayer *transportLayer, byte pin, std::string topicName) : Device(id, transportLayer) { 00034 _pin = pin; 00035 _topicName = topicName; 00036 } 00037 00038 void robotican_hardware::Switch::deviceAck(const DeviceAck *ack) { 00039 Device::deviceAck(ack); 00040 if(isReady()) { 00041 _switchState = _nodeHandle.advertise<std_msgs::Bool>(_topicName, 10); 00042 ros_utils::rosInfo("Switch is ready"); 00043 } 00044 else { 00045 ros_utils::rosError("RiCBoard can't build Switch object for spme reason, this program will shut down now"); 00046 ros::shutdown(); 00047 } 00048 } 00049 00050