Skip to content

Conversation

@naoki-mizuno
Copy link
Contributor

I've added a feature to reboot some of the servos using the a service. This is a WIP/RFC with some of the things I'm not sure about being:

  • Should the messages go into a different repository?
    • Normally people create a _msgs repository that only contains message and service files.
  • Are the messages reasonable? (in terms of names, members, and what they represent)
    • I feel like there's a better name/functionality than ServoID.msg.
  • Should the service be started in a private node handle?
    • Currently it's started as /reboot. Maybe putting it in /dynamixel_control_hw/reboot is better?
  • How should I check whether it's actually being rebooted?
    • When I call the service no errors are reported, but I will need to overload with torque
    • However, going over the torque limit is pretty difficult to do. Any suggestions?
  • Should the set_torque_enable be removed?
    • The reason why I put it in there is because after a reboot, the torque is switched off.
  • Is the sleep(0.1) appropriate
    • Probably not. But without it, I couldn't set the torque on after sending the packet

I'd be happy to know you guys' thoughts/suggestions!

@dogoepp dogoepp requested review from costashatz and dogoepp May 24, 2018 07:17

dynamixel::StatusPacket<Protocol2> status;
// Send reboot
dynamixel::instructions::Reboot<Protocol2> packet(id);
Copy link
Member

@dogoepp dogoepp May 24, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For this line and also line 418, I believe that we should use the template parameter Protocol.


// Control
// let the controller compute the new command (via the controller manager)
_controller_manager->update(ros::Time::now(), _elapsed_time);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe we should not call this method either when the mutex is already locked by the thread doing the reboot.


// Input
// get the hardware's state
dynamixel_access_mutex.lock();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe that it would be preferable to use trylock (but have little experience in threads) because we would not want the warning messages that are generated when this method takes too much time to execute.

@dogoepp
Copy link
Member

dogoepp commented May 24, 2018

Thanks for this RFC and work!

  1. I have no idea about the messages going in a different repository. Why should it be?
  2. the message definitions seem fine to me for the naming scheme and shape but I would rather have joint names be used than actuators IDs; the final user does not need to know this low level information.
  3. it seems indeed better, to avoid ambiguity, to have /reboot in the private namespace
  4. It seems to me that the only way to tell that an actuator has rebooted is to check for a value in RAM that has been reset, typically torque enable.
    Maybe I can test with torque overload, but we can also try with voltage limits, by setting it around 24.5V and raising the input voltage a bit. This I can do for sure.
  5. Good question. I would think that yes, we should enable the torque again. How else would you suggest that we do ?
  6. Maybe we can ping the actuators until they respond and then enable their torque ?

@dogoepp dogoepp removed the request for review from costashatz June 25, 2020 13:58
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants