ArduinoDAQ_LowLevel.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016-17, Universidad de Almeria
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 
36 #pragma once
37 
38 #include <mrpt/version.h>
39 #if MRPT_VERSION>=0x199
40 # include <mrpt/comms/CSerialPort.h>
41 using mrpt::comms::CSerialPort;
42 #else
45 #endif
46 
47 #ifdef HAVE_ROS
48 #include <ros/ros.h>
49 #include <std_msgs/UInt8.h>
50 #include <std_msgs/Bool.h>
51 #include <std_msgs/Float64.h>
52 #endif
53 
55 #include <arduinodaq2pc-structs.h>
56 #include <functional>
57 
58 
59 class ArduinoDAQ_LowLevel : public mrpt::utils::COutputLogger
60 {
61 public:
63  virtual ~ArduinoDAQ_LowLevel();
64 
65 #ifdef HAVE_ROS
66 
71  ros::NodeHandle m_nh;
72  ros::NodeHandle m_nh_params;
73 
74  std::vector<ros::Subscriber> m_sub_GPIO_outputs, m_sub_dac, m_sub_PWM_outputs;
75  ros::Publisher m_pub_ADC, m_pub_ENC, m_pub_ENC_ABS;
76 #endif
77 
78  void setSerialPort(const std::string &sSerialName) {
79  m_serial_port_name = sSerialName;
80  }
81  std::string getSerialPort() const {
82  return m_serial_port_name;
83  }
84 
87  bool initialize();
88 
90  bool iterate();
91 
92  bool CMD_GPIO_output(int pin, bool pinState);
93  bool CMD_DAC(int dac_index, double dac_value_volts);
94  bool CMD_ADC_START(const TFrameCMD_ADC_start_payload_t &enc_config);
95  bool CMD_ADC_STOP();
96  bool CMD_PWM(int pin_index, uint8_t pwm_value);
98  bool CMD_ENCODERS_STOP();
100  bool CMD_ENCODER_ABS_STOP();
101 
102  void set_ADC_readings_callback(const std::function<void(TFrame_ADC_readings_payload_t)> &f) {
103  m_adc_callback = f;
104  }
106  m_enc_callback = f;
107  }
110  }
111 
112 protected:
113  // Local class members:
114  std::string m_serial_port_name;
118 
119  // Local methods:
120  bool AttemptConnection();
121  bool IsConnected() const;
122  bool ReceiveFrameFromController(std::vector<uint8_t> &rx_data);
123  void processIncommingFrame(const std::vector<uint8_t> &rxFrame);
124  bool WriteBinaryFrame( const uint8_t *full_frame, const size_t full_frame_len);
126  const uint8_t *full_frame,
127  const size_t full_frame_len,
128  const int num_retries = 10,
129  const int retries_interval_ms = 40,
130  uint8_t expected_ans_opcode = 0 //<! 0 means the default convention: full_frame[1]+0x70,
131  );
132 
133  std::function<void(TFrame_ADC_readings_payload_t)> m_adc_callback;
134  std::function<void(TFrame_ENCODERS_readings_payload_t)> m_enc_callback;
135  std::function<void(TFrame_ENCODER_ABS_reading_payload_t)> m_encabs_callback;
136 
137 #ifdef HAVE_ROS
138  void daqSetDigitalPinCallback(int index, const std_msgs::Bool::ConstPtr& msg);
139  void daqSetDACCallback(int dac_index, const std_msgs::Float64::ConstPtr& msg);
140  void daqSetPWMCallback(int pwm_pin_index, const std_msgs::UInt8::ConstPtr& msg);
141 #endif
145 
146 };
void daqOnNewADCCallback(const TFrame_ADC_readings_payload_t &data)
bool CMD_GPIO_output(int pin, bool pinState)
Sets the clutch.
bool AttemptConnection()
Returns true if connected OK, false on error.
bool CMD_ADC_START(const TFrameCMD_ADC_start_payload_t &enc_config)
bool SendFrameAndWaitAnswer(const uint8_t *full_frame, const size_t full_frame_len, const int num_retries=10, const int retries_interval_ms=40, uint8_t expected_ans_opcode=0)
Sends a binary packet, in the expected format (returns false on COMMS error)
bool IsConnected() const
Returns true if the serial comms are working.
void daqOnNewENCCallback(const TFrame_ENCODERS_readings_payload_t &data)
bool CMD_DAC(int dac_index, double dac_value_volts)
void set_ENCODERS_readings_callback(const std::function< void(TFrame_ENCODERS_readings_payload_t)> &f)
void daqOnNewENCAbsCallback(const TFrame_ENCODER_ABS_reading_payload_t &data)
GLint GLenum GLsizei GLint GLsizei const GLvoid * data
std::function< void(TFrame_ADC_readings_payload_t)> m_adc_callback
std::function< void(TFrame_ENCODER_ABS_reading_payload_t)> m_encabs_callback
bool CMD_ENCODER_ABS_START(const TFrameCMD_EMS22A_start_payload_t &enc_config)
CSerialPort m_serial
The serial COMMS object.
GLuint index
std::string getSerialPort() const
bool CMD_ENCODERS_START(const TFrameCMD_ENCODERS_start_payload_t &enc_config)
std::function< void(TFrame_ENCODERS_readings_payload_t)> m_enc_callback
bool CMD_PWM(int pin_index, uint8_t pwm_value)
bool WriteBinaryFrame(const uint8_t *full_frame, const size_t full_frame_len)
Sends a binary packet, in the expected format (returns false on COMMS error)
_u16 pwm_value
void set_ADC_readings_callback(const std::function< void(TFrame_ADC_readings_payload_t)> &f)
unsigned char f
Definition: wiring.c:51
void setSerialPort(const std::string &sSerialName)
void set_ENCODER_ABS_readings_callback(const std::function< void(TFrame_ENCODER_ABS_reading_payload_t)> &f)
void processIncommingFrame(const std::vector< uint8_t > &rxFrame)
bool ReceiveFrameFromController(std::vector< uint8_t > &rx_data)
Tries to get a framed chunk of data from the controller.
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f


arduino_daq
Author(s):
autogenerated on Mon Jun 10 2019 12:46:03