Joystick2Velocity2D.cpp
Go to the documentation of this file.
1 // -*- C++ -*-
10 #include <rtm/idl/BasicDataType.hh>
11 #include <rtm/idl/ExtendedDataTypes.hh>
12 #include "hrpsys/util/VectorConvert.h"
13 #include "Joystick2Velocity2D.h"
14 
15 // Module specification
16 // <rtc-template block="module_spec">
17 static const char* joystick2velocity_spec[] =
18  {
19  "implementation_id", "Joystick2Velocity2D",
20  "type_name", "Joystick2Velocity2D",
21  "description", "joystick output to velocity converter",
22  "version", HRPSYS_PACKAGE_VERSION,
23  "vendor", "AIST",
24  "category", "example",
25  "activity_type", "DataFlowComponent",
26  "max_instance", "10",
27  "language", "C++",
28  "lang_type", "compile",
29  // Configuration variables
30  "conf.default.debugLevel", "0",
31  "conf.default.axesIds", "0,1,2",
32  "conf.default.scales", "1.0,1.0,1.0",
33  "conf.default.neutrals", "0.0,0.0,0.0",
34  ""
35  };
36 // </rtc-template>
37 
39  : RTC::DataFlowComponentBase(manager),
40  // <rtc-template block="initializer">
41  m_axesIn("axes", m_axes),
42  m_velOut("vel", m_vel),
43  // </rtc-template>
44  dummy(0),
45  m_debugLevel(0)
46 {
47  // Registration: InPort/OutPort/Service
48  // <rtc-template block="registration">
49  // Set InPort buffers
50 
51  // Set OutPort buffer
52 
53  // Set service provider to Ports
54 
55  // Set service consumers to Ports
56 
57  // Set CORBA Service Ports
58 
59  // </rtc-template>
60 }
61 
63 {
64 }
65 
66 
67 
69 {
70  //std::cout << m_profile.instance_name << ": onInitialize()" << std::endl;
71  // <rtc-template block="bind_config">
72  // Bind variables and configuration variable
73  bindParameter("debugLevel", m_debugLevel, "0");
74  bindParameter("axesIds", m_axesIds, "0,1,2");
75  bindParameter("scales", m_scales, "1.0,1.0,1.0");
76  bindParameter("neutrals", m_neutrals, "0.0,0.0,0.0");
77 
78  // </rtc-template>
79  addInPort("axes", m_axesIn);
80  addOutPort("vel", m_velOut);
81 
82  m_axes.data.length(4);
83  for (unsigned int i=0; i<m_axes.data.length(); i++){
84  m_axes.data[i] = 0.0;
85  }
86 
87  return RTC::RTC_OK;
88 }
89 
90 
91 
92 /*
93 RTC::ReturnCode_t Joystick2Velocity2D::onFinalize()
94 {
95  return RTC::RTC_OK;
96 }
97 */
98 
99 /*
100 RTC::ReturnCode_t Joystick2Velocity2D::onStartup(RTC::UniqueId ec_id)
101 {
102  return RTC::RTC_OK;
103 }
104 */
105 
106 /*
107 RTC::ReturnCode_t Joystick2Velocity2D::onShutdown(RTC::UniqueId ec_id)
108 {
109  return RTC::RTC_OK;
110 }
111 */
112 
114 {
115  return RTC::RTC_OK;
116 }
117 
119 {
120  return RTC::RTC_OK;
121 }
122 
124 {
125  if (m_debugLevel > 0){
126  std::cout << m_profile.instance_name<< ": onExecute(" << ec_id << ")"
127  << std::endl;
128  }
129 
130  if (m_axesIn.isNew()) m_axesIn.read();
131 
132  m_vel.data.vx = m_neutrals[0] + m_scales[0]*m_axes.data[m_axesIds[0]];
133  m_vel.data.vy = m_neutrals[1] + m_scales[1]*m_axes.data[m_axesIds[1]];
134  m_vel.data.va = m_neutrals[2] + m_scales[2]*m_axes.data[m_axesIds[2]];
135  if (m_debugLevel > 0) {
136  printf("velocity command: %5.2f %5.2f %5.2f",
137  m_vel.data.vx, m_vel.data.vy, m_vel.data.va);
138  }
139  m_velOut.write();
140 
141  return RTC::RTC_OK;
142 }
143 
144 /*
145 RTC::ReturnCode_t Joystick2Velocity2D::onAborting(RTC::UniqueId ec_id)
146 {
147  return RTC::RTC_OK;
148 }
149 */
150 
151 /*
152 RTC::ReturnCode_t Joystick2Velocity2D::onError(RTC::UniqueId ec_id)
153 {
154  return RTC::RTC_OK;
155 }
156 */
157 
158 /*
159 RTC::ReturnCode_t Joystick2Velocity2D::onReset(RTC::UniqueId ec_id)
160 {
161  return RTC::RTC_OK;
162 }
163 */
164 
165 /*
166 RTC::ReturnCode_t Joystick2Velocity2D::onStateUpdate(RTC::UniqueId ec_id)
167 {
168  return RTC::RTC_OK;
169 }
170 */
171 
172 /*
173 RTC::ReturnCode_t Joystick2Velocity2D::onRateChanged(RTC::UniqueId ec_id)
174 {
175  return RTC::RTC_OK;
176 }
177 */
178 
179 
180 
181 extern "C"
182 {
183 
185  {
187  manager->registerFactory(profile,
188  RTC::Create<Joystick2Velocity2D>,
189  RTC::Delete<Joystick2Velocity2D>);
190  }
191 
192 };
193 
194 
ComponentProfile m_profile
png_infop png_charpp int png_charpp profile
InPort< TimedFloatSeq > m_axesIn
joystick out to velocity converter
std::vector< unsigned int > m_axesIds
~Joystick2Velocity2D()
Destructor.
std::vector< double > m_neutrals
png_uint_32 i
bool addOutPort(const char *name, OutPortBase &outport)
static const char * joystick2velocity_spec[]
Joystick2Velocity2D(RTC::Manager *manager)
Constructor.
ExecutionContextHandle_t UniqueId
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
std::vector< double > m_scales
void Joystick2Velocity2DInit(RTC::Manager *manager)
OutPort< TimedVelocity2D > m_velOut
virtual RTC::ReturnCode_t onInitialize()
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
virtual bool isNew()
virtual bool write(DataType &value)
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
bool addInPort(const char *name, InPortBase &inport)
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:50