motion_module_tutorial.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 #include <stdio.h>
19 
20 using namespace thormang3;
21 
23  : control_cycle_msec_(8)
24 {
25  enable_ = false;
26  module_name_ = "test_motion_module"; // set unique module name
28 
29  result_["r_sho_pitch"] = new robotis_framework::DynamixelState();
30  result_["r_sho_roll"] = new robotis_framework::DynamixelState();
32 }
33 
35 {
36  queue_thread_.join();
37 }
38 
39 void MotionModuleTutorial::initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
40 {
41  control_cycle_msec_ = control_cycle_msec;
42  queue_thread_ = boost::thread(boost::bind(&MotionModuleTutorial::queueThread, this));
43 }
44 
46 {
47  ros::NodeHandle ros_node;
48  ros::CallbackQueue callback_queue;
49 
50  ros_node.setCallbackQueue(&callback_queue);
51 
52  /* subscriber */
53  sub1_ = ros_node.subscribe("/tutorial_topic", 10, &MotionModuleTutorial::topicCallback, this);
54 
55  /* publisher */
56  pub1_ = ros_node.advertise<std_msgs::Int16>("/tutorial_publish", 1, true);
57 
58  ros::WallDuration duration(control_cycle_msec_ / 1000.0);
59  while(ros_node.ok())
60  callback_queue.callAvailable(duration);
61 }
62 
63 void MotionModuleTutorial::topicCallback(const std_msgs::Int16::ConstPtr &msg)
64 {
65  std_msgs::Int16 msg_int16;
66  msg_int16.data = msg->data;
67  pub1_.publish(msg_int16);
68 }
69 
70 void MotionModuleTutorial::process(std::map<std::string, robotis_framework::Dynamixel *> dxls,
71  std::map<std::string, double> sensors)
72 {
73  if (enable_ == false)
74  return;
75 
76  for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_iter = result_.begin(); state_iter != result_.end();
77  state_iter++)
78  {
79  int32_t p_pos = dxls[state_iter->first]->dxl_state_->present_position_;
80  int32_t g_pos = dxls[state_iter->first]->dxl_state_->goal_position_;
81  }
82 
83  // ...
84 
85  result_["r_sho_pitch"]->goal_position_ = 0;
86  result_["r_sho_roll"]->goal_position_ = 0;
87  result_["r_el"]->goal_position_ = 0;
88 }
89 
91 {
92  return;
93 }
94 
96 {
97  return false;
98 }
99 
std::map< std::string, DynamixelState * > result_
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void process(std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
void setCallbackQueue(CallbackQueueInterface *queue)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void topicCallback(const std_msgs::Int16::ConstPtr &msg)
bool ok() const
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)


motion_module_tutorial
Author(s): Zerom , SCH , Kayman
autogenerated on Mon Jun 10 2019 15:37:41