Actin®  Version 5.1.0
Software for Robotics Simulation and Control
Remote Command API

Remote Command API

The remote command API is used for remotely or locally commanding the simulation in the actinViewer or actinRT.

Server Setup

To run this example, a server must be running. A server can be either an instance of the actinViewer which has loaded the remoteCommandServerPlugin, or an instance of actinRT running with the remoteCommandServerPlugin loaded. The actinViewer allows you to see what the state of the simulation is, and actinRT has no graphical user interface.

actinViewer as server

To setup the server using the first method; launch the actinViewer and load the remoteCommandServerPlugin from the Plugins -> Load Plugin menu. After loading this plugin you may be prompted with a windows security alert when running on Windows platform. Make sure to allow the application to receive commands from the network as shown below.

windowsAlertActinViewer.png
Windows Security Alert

After the plugin is loaded, start the simulation. The actinViewer is now able to receive commands from a remote command client.

play.png

actinRT as server

To use actinRT as a server, open a command prompt or terminal, and change directories into the bin directory.

cdIntoBin.png
CD into bin directory

Next run actinRT with the required command line arguments. Pass the actinRT application the name of the model (cyton.ecz default or user model) as well as the cytonPlugin.ecp (which actinRT uses to command the hardware), and the remoteCommandServerPlugin which actinRT uses to receive commands from the network.

runactinRT.png
Run actinRT

The remoteCommandServerPlugin may need permission to access the network. You may get a security alert on Window as shown below.

windowsAlertActinRT.png
Windows Security Alert

After starting actinRT, the simulation will be running as if it were running in the actinViewer. The simulation will initialize to the hardware position, the control system will run at the same rate, as well as update the hardware at the same rate. actinRT is essentially the actinViewer without a graphical user interface.

Methods

take a look at ecRemoteCommand.h

EC_REMOTECOMMANDAPI_DECL EcBoolean init(const EcString& ipAddress = "127.0.0.1");

/// This command is required before any of the other RemoteCommand. It /// initializes the connection between client and server (hardware) end. ///

Parameters
[in]ipAddressServer address to connect to ///
Returns
EcBoolean Success or failure of initialization

EC_REMOTECOMMANDAPI_DECL void shutdown();

/// Cleans up memory associated with network connection.

EC_REMOTECOMMANDAPI_DECL EcBoolean setJointValues(const EcRealVector& joints, const EcU32 manipIndex = 0);

/// Send joint angles to the hardware. By default it will send it to the /// first manipulator. ///

Parameters
[in]jointsVector of EcReal joint values in radians ///
[in]manipIndexIndex of manipulator to set ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setJointValuesABI(EcReal *joints, EcU32 jointSize, const EcU32 manipIndex = 0);

/// Send joint angles to the hardware. By default it will send it to the /// first manipulator. ///

Parameters
[in]jointsVector of EcReal joint values in radians ///
[in]amountof memory at joints (max) to fill). ///
[in]manipIndexIndex of manipulator to set ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcU32 getNumJoints(const EcU32 manipIndex = 0);

/// Get the number of joints for a given manipulator index.

EC_REMOTECOMMANDAPI_DECL EcBoolean getJointValues(EcRealVector& joints, EcU32 manipIndex = 0);

/// Retrieve joint angles from the server. By default it will retrieve them /// from the first manipulator. Joint velocities can also be retrieved. ///

Parameters
[out]jointsVector of EcReal joint values in radians ///
[in]manipIndexIndex of manipulator to set ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcInt32 getJointValuesABI(EcReal *joints, EcU32 jointSize, const EcU32 manipIndex = 0);

/// Send joint angles to the hardware. By default it will send it to the /// first manipulator. ///

Parameters
[in]jointsVector of EcReal joint values in radians ///
[in]amountof memory at joints (max) to fill). ///
[in]manipIndexIndex of manipulator to set ///
Returns
size of the joints that were available to copy, can be bigger than jointSize or < 0 on failure.

EC_REMOTECOMMANDAPI_DECL EcBoolean setControlDescriptor(const EcU32 descriptor, const EcU32 manipIndex = 0);

/// Specify a control descriptor to use for a particular manipulator. ///

Parameters
[in]descriptorDescriptor index ///
[in]manipIndexIndex of manipulator to set ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setEndEffectorSet(const EcU32 eeSet, const EcU32 manipIndex = 0);

/// Specify the end-effector set to use for a particular manipulator. ///

Parameters
[in]eeSetEnd-effector set index ///
[in]manipIndexIndex of manipulator to set ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationPathFile(const EcString& filename);

/// Specify a manipulation path file to use. ///

Parameters
[in]filenameFilename to of path file to load ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean startManipulation();

/// 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. ///

Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean stopManipulation();

/// 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. ///

Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setHardwareEnable(const EcBoolean enable);

/// Set the hardware enabled state. ///

Parameters
[in]enableState to set the hardware in ///
Returns
EcBoolean Whether this command was successfully issued

#if !defined(EC_NO_ACTIN) && !defined(EC_NO_BOOST) //--------------------------------------------------------------------------— // The following commands require the Actin SDK. //--------------------------------------------------------------------------—

EC_REMOTECOMMANDAPI_DECL EcBoolean setDesiredPlacement(const EcEndEffectorPlacement& placement, const EcU32 manipIndex = 0, const EcU32 endIndex = 0);

/// Set the desired end-effector placement for a single end-effector 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. ///

Parameters
[in]placementPlacement to set ///
[in]manipIndexManipulator to target ///
[in]endIndexEnd-effector to target

EC_REMOTECOMMANDAPI_DECL EcBoolean setDesiredPlacement(const EcManipulatorEndEffectorPlacement& placement, const EcU32 manipIndex = 0);

/// Set the desired end-effector placement for a manipulator (possibly several end-effectors). /// The simulation will then generate joint values (position and velocity) to move the EE from the current /// placement to the desired one. ///

Parameters
[in]placementPlacement to set ///
[in]manipIndexManipulator to target

EC_REMOTECOMMANDAPI_DECL EcBoolean getDesiredPlacement(EcManipulatorEndEffectorPlacement& placement, const EcU32 manipIndex = 0);

/// Retrieve the Desired end-effector placement. This is computed from the /// joint angles of the manipulator. ///

Parameters
[in]placementPlacement to retrieve ///
[in]manipIndexManipulator to target

EC_REMOTECOMMANDAPI_DECL EcBoolean getActualPlacement(EcManipulatorEndEffectorPlacement& placement, const EcU32 manipIndex = 0);

/// Retrieve the actual end-effector placement. This is computed from the /// joint angles of the manipulator. ///

Parameters
[in]placementPlacement to retrieve ///
[in]manipIndexManipulator to target

EC_REMOTECOMMANDAPI_DECL EcBoolean setControlMode(const EcU32 mode, const EcU32 manipIndex = 0);

/// Set the control mode of a manipulator. ///

Parameters
[in]modeControl mode to set (0 for position control and 1 for velocity control) ///
[in]manipIndexManipulator to target

EC_REMOTECOMMANDAPI_DECL EcBoolean setDesiredVelocity(const EcRealVector& velocity, const EcU32 manipIndex = 0, const EcU32 endIndex = 0);

/// Set the desired end-effector velocity for a single end-effector of a manipulator. The control mode must be in velocity control. ///

Parameters
[in]velocityVelocity (which is a vector of reals) to set. For example, for a point end effector, this vector would be of /// size 3 for the x, y, and z directions. For a frame end effector, this would be of size 6 – the first 3 for linear velocity /// and the second 3 for angular velocity. ///
[in]manipIndexManipulator to target ///
[in]endIndexEnd-effector to target ///
See also
setControlMode()

EC_REMOTECOMMANDAPI_DECL EcBoolean setDesiredVelocity(const EcManipulatorEndEffectorVelocity& velocity, const EcU32 manipIndex = 0);

/// Set the desired end-effector velocity for a manipulator (possibly several end-effectors). ///

Parameters
[in]veloictyVelocity to set ///
[in]manipIndexManipulator to target

typedef boost::function<void (EcBoolean, void*)> ManipulationCompleteCB;__

/// 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.

EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationDirector(const EcManipulationDirector& director);

/// Specify a manipulation director to use. ///

Parameters
[in]directorDirector to use ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationScript(const EcManipulationScript& script);

/// Specify a manipulation script to use. ///

Parameters
[in]scriptScript to use ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationActionManager(const EcManipulationActionManager& manager);

/// Specify a manipulation action manager to use. ///

Parameters
[in]managerManipulation action manager to use ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationAction(const EcString& actionName);

/// 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. ///

Parameters
[in]actionNameName of manipulation action to execute. ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setManipulationCompletedCallback(ManipulationCompleteCB cb, void* data = NULL);

/// Optional callback registration to be notified when a manipulation action, a manipulation script or /// a path planning action has finished. The callback argument value will receive either EcTrue for a /// successful completion, or EcFalse for prematurely-terminated or failure. ///

Parameters
[in]cbCallback function to register ///
[in]dataOptional pointer to user data to pass along ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setPathPlanner(const EcRrtPathPlanner& planner);

/// Specify a path planner to use for path planning. ///

Parameters
[in]plannerA path planner to use ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setPathPlanningDesiredPlacement(const EcManipulatorEndEffectorPlacement& placement);

/// Move the manipulator to the specified placement using path planning. Note that at present, this method /// only support the first manipulator (index 0). ///

Parameters
[in]placementThe desired placement ///
Returns
EcBoolean Whether this command was successfully issued

EC_REMOTECOMMANDAPI_DECL EcBoolean setPathPlanningDesiredPlacement(const EcEndEffectorPlacement& placement, const EcU32 endIndex = 0);

/// Move the manipulator to the specified placement using path planning. Note that at present, this method /// only support the first manipulator (index 0). ///

Parameters
[in]placementThe desired placement ///
Returns
EcBoolean Whether this command was successfully issued
Created by Energid Technologies www.energid.com
Copyright © 2016 Energid. All trademarks mentioned in this document are property of their respective owners.