23 : control_cycle_msec_(8)
56 pub1_ = ros_node.
advertise<std_msgs::Int16>(
"/tutorial_publish", 1,
true);
65 std_msgs::Int16 msg_int16;
66 msg_int16.data = msg->data;
71 std::map<std::string, double> sensors)
76 for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_iter =
result_.begin(); state_iter !=
result_.end();
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_;
85 result_[
"r_sho_pitch"]->goal_position_ = 0;
86 result_[
"r_sho_roll"]->goal_position_ = 0;
87 result_[
"r_el"]->goal_position_ = 0;
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())
ControlMode control_mode_
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)
virtual ~MotionModuleTutorial()
void topicCallback(const std_msgs::Int16::ConstPtr &msg)
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
boost::thread queue_thread_