00001 /* 00002 * Copyright (c) 2010, Bosch LLC 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Bosch LLC nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 //\Author Joerg Wagner, Bosch LLC 00031 00032 #include "skin_config/config_skin.h" 00033 #include <iostream> 00034 00035 SkinConfig::SkinConfig() 00036 { 00037 //initialize values 00038 ui8sensor_number_ = 0; 00039 ui8dyn_thres_currentvalue_ = 255; 00040 dtime_subscription_ = ros::Time::now(); 00041 00042 //ROS Subscriber 00043 skin_sub_ = nh_.subscribe("skin_data", 100, &SkinConfig::skin_Callback, this);//Topic: skin_data 00044 00045 //ROS Client 00046 config_client = nh_.serviceClient<skin_driver::skin_serv>("skin_serv");//Service: skin_serv 00047 } 00048 00049 void SkinConfig::skin_Callback(const boost::shared_ptr<skin_driver::skin_meas const>& msg)//callback function 00050 { 00051 ui8sensor_number_ = msg->sensor_number_msg; 00052 dtime_subscription_ = msg->header.stamp; 00053 ui8dyn_thres_currentvalue_ = msg->dyn_thres_cv_msg; 00054 00055 std::cout << "skin_Callback" << " \n"; 00056 } 00057 00058 bool SkinConfig::OnRequestChanges(const uint8_t start_adr[2], const uint8_t steps, const uint8_t number_of_bytes, uint8_t write_data, bool sens_num_change) 00059 { 00060 if(bskin_driver_node_online == true) 00061 { 00062 srv_.request.header.stamp = ros::Time::now(); 00063 srv_.request.start_adr_srv[0] = start_adr[0]; 00064 srv_.request.start_adr_srv[1] = start_adr[1]; 00065 srv_.request.steps_srv = steps; 00066 srv_.request.number_of_bytes_srv = number_of_bytes; 00067 srv_.request.write_data_srv = write_data; 00068 srv_.request.sens_num_change_srv = sens_num_change; 00069 00070 if(config_client.call(srv_)) 00071 { 00072 return srv_.response.write_to_skin_successful_srv; 00073 } 00074 else 00075 { 00076 return false; 00077 } 00078 } 00079 else 00080 { 00081 return false; 00082 } 00083 } 00084 00085 00086 00087 00088 00089 00090 00091 00092 00093 00094 00095