Remote Command API Tutorial
Remote Command API Tutorial
Remote Command API Tutorial
This tutorial covers the configuration, and building of example code for the remote command api for Robai Cytons.
Assumptions:
Cyton Gamma Viewer (either 300 or 1500) from 2013-06-20 or later installed. cytonViewer.exe launches without error and all joints are moveable (click the Numerical Configuration of Manipulators button then move the slider bars, the Cyton should move in hardware and in simulation). Visual Studio 2010 installed (Express is supported)
6. You should now see a guide frame at the base of the robot gripper. This gripper is by default a Point End Effector which places constraints (controls) only the position of the robot end effector 7. To switch to a Frame End Effector which constrains the position and orientation, select Edit>Position Control System->Active Control Parameters
The guide frame will now be aligned to the coordinate frame of the end effector 9. Select Simulation->Dragger from the menu bar. The dragger is an intuitive control for defining the placement and orientation of an end effector in the simulation.
10. Click Dragger Pose to show the dragger then close the dialog
11. Click the View mode button to enable changing the view with the mouse (left click and drag -> rotate, right click and drag -> pan) 12. Click the Hardware State button to begin sending position commands to the hardware and click the Play button to start running the simulation 13. Click and drag either a dragger arrow or ring to move the hardware in that direction
Creating sequences
1. In the Manipulation Actions panel, click the Add action (green plus) button
2. Give the action the name Square and make sure that waypointSequence is selected as the action type
3. Using the dragger, align the end effector to the primary axes
4. In the blank box under End Effector: in the Manipulation Actions panel, right click and select Add waypoint 5. Using the dragger, move the end effector to the other three corners of an imaginary square, stopping at each corner and adding a waypoint via step 4, until you have 4 waypoints
6.
Select Show all waypoints to see the waypoints you have created
7. In order to insure that the end effector returns to its original position at the end of the sequence, right click the first waypoint and select Move To Waypoint. 8. Using the same procedure as step 4, add this position as waypoint 5. 9. Click the Execute button to the left of the sequence drop down menu to run the sequence
10. Finally, save the sequence by clicking the Save manipulation action manager button under the Manipulation Actions label as my_sequence_library.ecam in the bin directory of the installer
Editing waypoints
You may notice with the sequence just created that the Cyton will not make a sharp square, but will cut and round out the corners 1. Select a waypoint from the waypoint list 2. Click the Waypoint Properties button to show a table of properties governing the behavior of the Cyton at that point 3. Reduce the zoneRadius property to a small value such as 0.001 (1 millimeter) for each waypoint in the waypoint list 4. Running the sequence should produce a much sharper square 5. Remember to save using the manipulation action save button after you are finished making changes to the waypoints
2. Workaround for Boost library missing include: a. In the solution explorer, highlight the testPlugins-testRemoteCommand project then right click and select Properties
b. Expand the C/C++ subsection and then select the General subsection under that.
c. Click in the Additional Include Directories field then the drop-down arrow then <Edit>
d. Click the line ..\..\..\..\external, and then the button. Navigate to the boost include folder and click Select Folder (The line should read something like: C:\Program Files (x86)\Robai\<Installer_Name>\external\boost-20130409-msvc2010i386\boost_1_53_0\include)
f.
g. In the solution explorer, highlight the testPlugins-testRemoteCommand project then right click and select Build h. When the build is finished, you should see: ========== Build: 1 succeeded, 0 failed, 0 up-to-date, 0 skipped ========== in the output window.
2. On line 117, edit the line to reflect the name of the manipulation action manager you created earlier (The line should read: EcString filename = cytonDir + "/my_sequence_library.ecam";
3. Open blah and edit both line 179 and 199 to reflect the name of the action you created earlier (Each line should read: retVal = setManipulationAction("Square");
remoteCommandServerPlugin.ecp
4. Leave the server running in the background (DO NOT press Return )
4. The Cyton should move in a square, pause, then move in a square again
EC_REMOTECOMMANDAPI_DECL EcBoolean init(const EcString& ipAddress = "127.0.0.1", cons t EcString& simulationFileName = ""); /// Cleans up memory associated with network connection. EC_REMOTECOMMANDAPI_DECL void shutdown(); /// Send joint angles to the hardware. By default it will send it to the /// first manipulator. /// @param[in] joints Vector of EcReal joint values in radians /// @param[in] manipIndex Index of manipulator to set /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setJointValues(const EcRealVector& joints, const E cU32 manipIndex = 0); /// Retrieve joint angles from the server. By default it will retrieve them /// from the first manipulator. Joint velocities can also be retrieved. /// @param[out] joints Vector of EcReal joint values in radians /// @param[in] manipIndex Index of manipulator to set /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean getJointValues(EcRealVector& joints, EcU32 manipIn dex = 0); /// Specify a control descriptor to use for a particular manipulator. /// @param[in] descriptor Descriptor index /// @param[in] manipIndex Index of manipulator to set /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setControlDescriptor(const EcU32 descriptor, const EcU32 manipIndex = 0); /// Specify the end-effector set to use for a particular manipulator. /// @param[in] eeSet End-effector set index /// @param[in] manipIndex Index of manipulator to set /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setEndEffectorSet(const EcU32 eeSet, const EcU32 m anipIndex = 0); /// Specify a manipulation path file to use. /// @param[in] filename Filename to of path file to load /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationPathFile(const EcString& filename); /// Start a manipulation task specified previously with setManipulationScript(), /// setManipulationAction(), or setManipulationPathFile(). No other /// manipulation commands are allowed to be issued once a sequence has started /// except stopManipulation(). If a manipulation completion callback /// was registered, the completion status of the sequence will be sent when /// finished. /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean startManipulation(); /// /// /// /// /// Stops a manipulation script that is in progress from startManipulation(). If a manipulation completion callback was registered, it will receive a hpcsm::StatusFailed message due to premature termination. @return EcBoolean Whether this command was successfully issued
EC_REMOTECOMMANDAPI_DECL EcBoolean stopManipulation(); /// Set the hardware enabled state. /// @param[in] enable State to set the hardware in /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setHardwareEnable(const EcBoolean enable);
//----------------------------------------------------------------------------// The following commands require the Actin SDK. //----------------------------------------------------------------------------/// Set the desired end-effector placement for a single endeffector of a manipulator. The simulation will then generate /// joint values (position and velocity) to move the EE from the current /// placement to the desired one. /// @param[in] placement Placement to set /// @param[in] manipIndex Manipulator to target /// @param[in] endIndex End-effector to target EC_REMOTECOMMANDAPI_DECL EcBoolean setDesiredPlacement(const EcEndEffectorPlacement& placement, const EcU32 manipIndex = 0, const EcU32 endIndex = 0); /// Set the desired end-effector placement for a manipulator (possibly several endeffectors). /// The simulation will then generate joint values (position and velocity) to move th e EE from the current /// placement to the desired one. /// @param[in] placement Placement to set /// @param[in] manipIndex Manipulator to target EC_REMOTECOMMANDAPI_DECL EcBoolean setDesiredPlacement(const EcManipulatorEndEffector Placement& placement, const EcU32 manipIndex = 0); /// Retrieve the actual end-effector placement. This is computed from the /// joint angles of the manipulator. /// @param[in] placement Placement to retrieve /// @param[in] manipIndex Manipulator to target EC_REMOTECOMMANDAPI_DECL EcBoolean getDesiredPlacement(EcManipulatorEndEffectorPlacem ent& placement, const EcU32 manipIndex = 0); /// Function signature for receiving manipulation completed messages. The /// completion value and a pointer to user data (specified at registration) /// will be passed in as the arguments. typedef boost::function<void (EcBoolean, void*)> ManipulationCompleteCB; /// Specify a manipulation director to use. /// @param[in] director Director to use /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationDirector(const EcManipulationDirect or& director); /// Specify a manipulation script to use. /// @param[in] script Script to use /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationScript(const EcManipulationScript& script);
/// Specify a manipulation action manager to use. /// @param[in] manager Manipulation action manager to use /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationActionManager(const EcManipulationA ctionManager& manager); /// Specify a name of manipulation action to execute. The action name must be in the action manager. Thus, this must /// be called AFTER a call to setManipulationActionManager. /// @param[in] actionName Name of manipulation action to execute. /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationAction(const EcString& actionName); /// Optional callback registration to be notified when a manipulation action /// has finished. The callback argument value will receive either EcTrue for a /// successful completion, or EcFalse for prematurely-terminated or failure. /// @param[in] cb Callback function to register /// @param[in] data Optional pointer to user data to pass along /// @return EcBoolean Whether this command was successfully issued EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationCompletedCallback(ManipulationCompl eteCB cb, void* data = NULL);